diff --git a/software/firmware/pan_tilt/pan_tilt.ino b/software/firmware/chassis_pan_tilt/chassis_pan_tilt.ino similarity index 100% rename from software/firmware/pan_tilt/pan_tilt.ino rename to software/firmware/chassis_pan_tilt/chassis_pan_tilt.ino diff --git a/software/firmware/iris/iris.ino b/software/firmware/iris/iris.ino index 95c2b6e..437028a 100644 --- a/software/firmware/iris/iris.ino +++ b/software/firmware/iris/iris.ino @@ -1,9 +1,33 @@ -void setup() { - // put your setup code here, to run once: +#include "SBUS.h" +#include +SBUS x8r(Serial3); + +const char num_modbus_channels = 16; //Being explicit so I get errors if I try to do something stupid +uint16_t modbus_data[num_modbus_channels] = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0 , 0 , 0, 0, 0, 0, 0}; + +Modbus slave(1, 2, 0); + +uint16_t channels[16]; +uint8_t failSafe; +uint16_t lostFrames = 0; + +const char bad_pins[] = {3, 4, 23, 24,}; + +void setup() { + for (int i = 0 ; i < sizeof(bad_pins) / sizeof(bad_pins[0]) ; i++) { + pinMode(bad_pins[i], INPUT); + } + + pinMode(8, INPUT_PULLUP); + + // analogWriteResolution(16); + x8r.begin(); + slave.begin(2000000); // baud-rate at 19200 } void loop() { - // put your main code here, to run repeatedly: + x8r.read(&channels[0], &failSafe, &lostFrames); + slave.poll( channels, num_modbus_channels ); } diff --git a/software/firmware/libraries/Adafruit_BNO055_t3/Adafruit_BNO055_t3.cpp b/software/firmware/libraries/Adafruit_BNO055_t3/Adafruit_BNO055_t3.cpp new file mode 100644 index 0000000..2386ec9 --- /dev/null +++ b/software/firmware/libraries/Adafruit_BNO055_t3/Adafruit_BNO055_t3.cpp @@ -0,0 +1,718 @@ +/*************************************************************************** + This is a library for the BNO055 orientation sensor + + Designed specifically to work with the Adafruit BNO055 Breakout. + + Pick one up today in the adafruit shop! + ------> http://www.adafruit.com/products + + These sensors use I2C to communicate, 2 pins are required to interface. + + Adafruit invests time and resources providing this open source code, + please support Adafruit andopen-source hardware by purchasing products + from Adafruit! + + Written by KTOWN for Adafruit Industries. + + !!!!!MODIFIED VERSION TO USE I2C_T3 LIBRARY FOR TEENSY INSTEAD OF WIRE + IN ORDER TO USE TEENSY'S BOTH I2C PORTS + Roald Baudoux - 2016-03 + + Updated 2016-03-15: i2c_bus type defined to set choice of Wire or Wire1 + Updated 2016-08-17: added delay of 30 ms after function call "write8(BNO055_SYS_TRIGGER_ADDR, 0x20);" + + MIT license, all text above must be included in any redistribution + ***************************************************************************/ + +#if ARDUINO >= 100 +#include "Arduino.h" +#else +#include "WProgram.h" +#endif + +#include +#include + +#include "Adafruit_BNO055_t3.h" // MODIFIED RB + +/*************************************************************************** + CONSTRUCTOR + ***************************************************************************/ + +/**************************************************************************/ +/*! + @brief Instantiates a new Adafruit_BNO055 class + + !!!!! MODIFIED TO BE COMPATIBLE WITH I2C_T3 library instead of Wire + // Params : I2C bus, sensor ID, address, I2C mode (master/slave), pins, pullups, freq, opMode (interrupt/DMA/immediate) + */ +/**************************************************************************/ +// OLD : Adafruit_BNO055::Adafruit_BNO055(int32_t sensorID, uint8_t address) +Adafruit_BNO055::Adafruit_BNO055(i2c_bus iBus, int32_t sensorID, uint8_t aAddress, i2c_mode iMode, i2c_pins pins, i2c_pullup pullup, i2c_rate iRate, i2c_op_mode opeMode) +{ + _iBus = iBus; // ADDED RB 0 for Wire() and 1 for Wire1(); + _sensorID = sensorID; + _aAddress = aAddress; + _iMode = iMode; // ADDED RB + _pins = pins; // ADDED RB + _pullup = pullup; // ADDED RB + _iRate = iRate; // ADDED RB + _opeMode = opeMode; // ADDED RB +} + +/*************************************************************************** + PUBLIC FUNCTIONS + ***************************************************************************/ + +/**************************************************************************/ +/*! + @brief Sets up the HW + */ +/**************************************************************************/ +bool Adafruit_BNO055::begin(adafruit_bno055_opmode_t aMode) +{ + /* Enable I2C */ + + if (_iBus == WIRE_BUS) + { + Wire.begin(_iMode, _aAddress, _pins, _pullup, _iRate, _opeMode); + } + else + { + Wire1.begin(_iMode, _aAddress, _pins, _pullup, _iRate, _opeMode); + } + /* Make sure we have the right device */ + uint8_t id = read8(BNO055_CHIP_ID_ADDR); + if(id != BNO055_ID) + { + delay(1000); + id = read8(BNO055_CHIP_ID_ADDR); + if(id != BNO055_ID) { + return false; // still not? ok bail + } + } + /* Switch to config mode (just in case since this is the default) */ + setMode(OPERATION_MODE_CONFIG); + + /* Reset */ + write8(BNO055_SYS_TRIGGER_ADDR, 0x20); + delay(30); // ADDED RB + + while (read8(BNO055_CHIP_ID_ADDR) != BNO055_ID) + { + delay(10); + } + delay(50); + + /* Set to normal power mode */ + write8(BNO055_PWR_MODE_ADDR, POWER_MODE_NORMAL); + delay(10); + write8(BNO055_PAGE_ID_ADDR, 0); + + + /* Set the output units */ + /* + uint8_t unitsel = (0 << 7) | // Orientation = Android + (0 << 4) | // Temperature = Celsius + (0 << 2) | // Euler = Degrees + (1 << 1) | // Gyro = Rads + (0 << 0); // Accelerometer = m/s^2 + write8(BNO055_UNIT_SEL_ADDR, unitsel); + */ + + /* Configure axis mapping (see section 3.4) */ + /* + write8(BNO055_AXIS_MAP_CONFIG_ADDR, REMAP_CONFIG_P2); // P0-P7, Default is P1 + delay(10); + write8(BNO055_AXIS_MAP_SIGN_ADDR, REMAP_SIGN_P2); // P0-P7, Default is P1 + delay(10); + */ + + write8(BNO055_SYS_TRIGGER_ADDR, 0x0); + delay(10); + /* Set the requested operating mode (see section 3.3) */ + setMode(aMode); + delay(20); + + return true; +} + +/**************************************************************************/ +/*! + @brief Puts the chip in the specified operating mode + */ +/**************************************************************************/ +void Adafruit_BNO055::setMode(adafruit_bno055_opmode_t aMode) +{ + _aMode = aMode; + write8(BNO055_OPR_MODE_ADDR, _aMode); + delay(30); +} + +/**************************************************************************/ +/*! + @brief Use the external 32.768KHz crystal + */ +/**************************************************************************/ +void Adafruit_BNO055::setExtCrystalUse(boolean usextal) +{ + adafruit_bno055_opmode_t modeback = _aMode; + + /* Switch to config mode (just in case since this is the default) */ + setMode(OPERATION_MODE_CONFIG); + delay(25); + write8(BNO055_PAGE_ID_ADDR, 0); + if (usextal) { + write8(BNO055_SYS_TRIGGER_ADDR, 0x80); + } else { + write8(BNO055_SYS_TRIGGER_ADDR, 0x00); + } + delay(10); + /* Set the requested operating mode (see section 3.3) */ + setMode(modeback); + delay(20); +} + + +/**************************************************************************/ +/*! + @brief Gets the latest system status info + */ +/**************************************************************************/ +void Adafruit_BNO055::getSystemStatus(uint8_t *system_status, uint8_t *self_test_result, uint8_t *system_error) +{ + write8(BNO055_PAGE_ID_ADDR, 0); + + /* System Status (see section 4.3.58) + --------------------------------- + 0 = Idle + 1 = System Error + 2 = Initializing Peripherals + 3 = System Iniitalization + 4 = Executing Self-Test + 5 = Sensor fusio algorithm running + 6 = System running without fusion algorithms */ + + if (system_status != 0) + *system_status = read8(BNO055_SYS_STAT_ADDR); + + /* Self Test Results (see section ) + -------------------------------- + 1 = test passed, 0 = test failed + + Bit 0 = Accelerometer self test + Bit 1 = Magnetometer self test + Bit 2 = Gyroscope self test + Bit 3 = MCU self test + + 0x0F = all good! */ + + if (self_test_result != 0) + *self_test_result = read8(BNO055_SELFTEST_RESULT_ADDR); + + /* System Error (see section 4.3.59) + --------------------------------- + 0 = No error + 1 = Peripheral initialization error + 2 = System initialization error + 3 = Self test result failed + 4 = Register map value out of range + 5 = Register map address out of range + 6 = Register map write error + 7 = BNO low power mode not available for selected operat ion mode + 8 = Accelerometer power mode not available + 9 = Fusion algorithm configuration error + A = Sensor configuration error */ + + if (system_error != 0) + *system_error = read8(BNO055_SYS_ERR_ADDR); + + delay(200); +} + +/**************************************************************************/ +/*! + @brief Gets the chip revision numbers + */ +/**************************************************************************/ +void Adafruit_BNO055::getRevInfo(adafruit_bno055_rev_info_t* info) +{ + uint8_t a, b; + + memset(info, 0, sizeof(adafruit_bno055_rev_info_t)); + + /* Check the accelerometer revision */ + info->accel_rev = read8(BNO055_ACCEL_REV_ID_ADDR); + + /* Check the magnetometer revision */ + info->mag_rev = read8(BNO055_MAG_REV_ID_ADDR); + + /* Check the gyroscope revision */ + info->gyro_rev = read8(BNO055_GYRO_REV_ID_ADDR); + + /* Check the SW revision */ + info->bl_rev = read8(BNO055_BL_REV_ID_ADDR); + + a = read8(BNO055_SW_REV_ID_LSB_ADDR); + b = read8(BNO055_SW_REV_ID_MSB_ADDR); + info->sw_rev = (((uint16_t)b) << 8) | ((uint16_t)a); +} + +/**************************************************************************/ +/*! + @brief Gets current calibration state. Each value should be a uint8_t + pointer and it will be set to 0 if not calibrated and 3 if + fully calibrated. + */ +/**************************************************************************/ +void Adafruit_BNO055::getCalibration(uint8_t* sys, uint8_t* gyro, uint8_t* accel, uint8_t* mag) { + uint8_t calData = read8(BNO055_CALIB_STAT_ADDR); + if (sys != NULL) { + *sys = (calData >> 6) & 0x03; + } + if (gyro != NULL) { + *gyro = (calData >> 4) & 0x03; + } + if (accel != NULL) { + *accel = (calData >> 2) & 0x03; + } + if (mag != NULL) { + *mag = calData & 0x03; + } +} + +/**************************************************************************/ +/*! + @brief Gets the temperature in degrees celsius + */ +/**************************************************************************/ +int8_t Adafruit_BNO055::getTemp(void) +{ + int8_t temp = (int8_t)(read8(BNO055_TEMP_ADDR)); + return temp; +} + +/**************************************************************************/ +/*! + @brief Gets a vector reading from the specified source + */ +/**************************************************************************/ +imu::Vector<3> Adafruit_BNO055::getVector(adafruit_vector_type_t vector_type) +{ + imu::Vector<3> xyz; + uint8_t buffer[6]; + memset (buffer, 0, 6); + + int16_t x, y, z; + x = y = z = 0; + + /* Read vector data (6 bytes) */ + readLen((adafruit_bno055_reg_t)vector_type, buffer, 6); + + x = ((int16_t)buffer[0]) | (((int16_t)buffer[1]) << 8); + y = ((int16_t)buffer[2]) | (((int16_t)buffer[3]) << 8); + z = ((int16_t)buffer[4]) | (((int16_t)buffer[5]) << 8); + + /* Convert the value to an appropriate range (section 3.6.4) */ + /* and assign the value to the Vector type */ + switch(vector_type) + { + case VECTOR_MAGNETOMETER: + /* 1uT = 16 LSB */ + xyz[0] = ((double)x)/16.0; + xyz[1] = ((double)y)/16.0; + xyz[2] = ((double)z)/16.0; + break; + case VECTOR_GYROSCOPE: + /* 1rps = 900 LSB */ + xyz[0] = ((double)x)/900.0; + xyz[1] = ((double)y)/900.0; + xyz[2] = ((double)z)/900.0; + break; + case VECTOR_EULER: + /* 1 degree = 16 LSB */ + xyz[0] = ((double)x)/16.0; + xyz[1] = ((double)y)/16.0; + xyz[2] = ((double)z)/16.0; + break; + case VECTOR_ACCELEROMETER: + case VECTOR_LINEARACCEL: + case VECTOR_GRAVITY: + /* 1m/s^2 = 100 LSB */ + xyz[0] = ((double)x)/100.0; + xyz[1] = ((double)y)/100.0; + xyz[2] = ((double)z)/100.0; + break; + } + + return xyz; +} + +/**************************************************************************/ +/*! + @brief Gets a quaternion reading from the specified source + */ +/**************************************************************************/ +imu::Quaternion Adafruit_BNO055::getQuat(void) +{ + uint8_t buffer[8]; + memset (buffer, 0, 8); + + int16_t x, y, z, w; + x = y = z = w = 0; + + /* Read quat data (8 bytes) */ + readLen(BNO055_QUATERNION_DATA_W_LSB_ADDR, buffer, 8); + w = (((uint16_t)buffer[1]) << 8) | ((uint16_t)buffer[0]); + x = (((uint16_t)buffer[3]) << 8) | ((uint16_t)buffer[2]); + y = (((uint16_t)buffer[5]) << 8) | ((uint16_t)buffer[4]); + z = (((uint16_t)buffer[7]) << 8) | ((uint16_t)buffer[6]); + + /* Assign to Quaternion */ + /* See http://ae-bst.resource.bosch.com/media/products/dokumente/bno055/BST_BNO055_DS000_12~1.pdf + 3.6.5.5 Orientation (Quaternion) */ + const double scale = (1.0 / (1<<14)); + imu::Quaternion quat(scale * w, scale * x, scale * y, scale * z); + return quat; +} + +/**************************************************************************/ +/*! + @brief Provides the sensor_t data for this sensor + */ +/**************************************************************************/ +void Adafruit_BNO055::getSensor(sensor_t *sensor) +{ + /* Clear the sensor_t object */ + memset(sensor, 0, sizeof(sensor_t)); + + /* Insert the sensor name in the fixed length char array */ + strncpy (sensor->name, "BNO055", sizeof(sensor->name) - 1); + sensor->name[sizeof(sensor->name)- 1] = 0; + sensor->version = 1; + sensor->sensor_id = _sensorID; + sensor->type = SENSOR_TYPE_ORIENTATION; + sensor->min_delay = 0; + sensor->max_value = 0.0F; + sensor->min_value = 0.0F; + sensor->resolution = 0.01F; +} + +/**************************************************************************/ +/*! + @brief Reads the sensor and returns the data as a sensors_event_t + */ +/**************************************************************************/ +bool Adafruit_BNO055::getEvent(sensors_event_t *event) +{ + /* Clear the event */ + memset(event, 0, sizeof(sensors_event_t)); + + event->version = sizeof(sensors_event_t); + event->sensor_id = _sensorID; + event->type = SENSOR_TYPE_ORIENTATION; + event->timestamp = millis(); + + /* Get a Euler angle sample for orientation */ + imu::Vector<3> euler = getVector(Adafruit_BNO055::VECTOR_EULER); + event->orientation.x = euler.x(); + event->orientation.y = euler.y(); + event->orientation.z = euler.z(); + + return true; +} + +/**************************************************************************/ +/*! + @brief Reads the sensor's offset registers into a byte array + */ +/**************************************************************************/ +bool Adafruit_BNO055::getSensorOffsets(uint8_t* calibData) +{ + if (isFullyCalibrated()) + { + adafruit_bno055_opmode_t lastMode = _aMode; + setMode(OPERATION_MODE_CONFIG); + + readLen(ACCEL_OFFSET_X_LSB_ADDR, calibData, NUM_BNO055_OFFSET_REGISTERS); + + setMode(lastMode); + return true; + } + return false; +} + +/**************************************************************************/ +/*! + @brief Reads the sensor's offset registers into an offset struct + */ +/**************************************************************************/ +bool Adafruit_BNO055::getSensorOffsets(adafruit_bno055_offsets_t &offsets_type) +{ + if (isFullyCalibrated()) + { + adafruit_bno055_opmode_t lastMode = _aMode; + setMode(OPERATION_MODE_CONFIG); + delay(25); + + offsets_type.accel_offset_x = (read8(ACCEL_OFFSET_X_MSB_ADDR) << 8) | (read8(ACCEL_OFFSET_X_LSB_ADDR)); + offsets_type.accel_offset_y = (read8(ACCEL_OFFSET_Y_MSB_ADDR) << 8) | (read8(ACCEL_OFFSET_Y_LSB_ADDR)); + offsets_type.accel_offset_z = (read8(ACCEL_OFFSET_Z_MSB_ADDR) << 8) | (read8(ACCEL_OFFSET_Z_LSB_ADDR)); + + offsets_type.gyro_offset_x = (read8(GYRO_OFFSET_X_MSB_ADDR) << 8) | (read8(GYRO_OFFSET_X_LSB_ADDR)); + offsets_type.gyro_offset_y = (read8(GYRO_OFFSET_Y_MSB_ADDR) << 8) | (read8(GYRO_OFFSET_Y_LSB_ADDR)); + offsets_type.gyro_offset_z = (read8(GYRO_OFFSET_Z_MSB_ADDR) << 8) | (read8(GYRO_OFFSET_Z_LSB_ADDR)); + + offsets_type.mag_offset_x = (read8(MAG_OFFSET_X_MSB_ADDR) << 8) | (read8(MAG_OFFSET_X_LSB_ADDR)); + offsets_type.mag_offset_y = (read8(MAG_OFFSET_Y_MSB_ADDR) << 8) | (read8(MAG_OFFSET_Y_LSB_ADDR)); + offsets_type.mag_offset_z = (read8(MAG_OFFSET_Z_MSB_ADDR) << 8) | (read8(MAG_OFFSET_Z_LSB_ADDR)); + + offsets_type.accel_radius = (read8(ACCEL_RADIUS_MSB_ADDR) << 8) | (read8(ACCEL_RADIUS_LSB_ADDR)); + offsets_type.mag_radius = (read8(MAG_RADIUS_MSB_ADDR) << 8) | (read8(MAG_RADIUS_LSB_ADDR)); + + setMode(lastMode); + return true; + } + return false; +} + + +/**************************************************************************/ +/*! + @brief Writes an array of calibration values to the sensor's offset registers + */ +/**************************************************************************/ +void Adafruit_BNO055::setSensorOffsets(const uint8_t* calibData) +{ + adafruit_bno055_opmode_t lastMode = _aMode; + setMode(OPERATION_MODE_CONFIG); + delay(25); + + /* A writeLen() would make this much cleaner */ + write8(ACCEL_OFFSET_X_LSB_ADDR, calibData[0]); + write8(ACCEL_OFFSET_X_MSB_ADDR, calibData[1]); + write8(ACCEL_OFFSET_Y_LSB_ADDR, calibData[2]); + write8(ACCEL_OFFSET_Y_MSB_ADDR, calibData[3]); + write8(ACCEL_OFFSET_Z_LSB_ADDR, calibData[4]); + write8(ACCEL_OFFSET_Z_MSB_ADDR, calibData[5]); + + write8(GYRO_OFFSET_X_LSB_ADDR, calibData[6]); + write8(GYRO_OFFSET_X_MSB_ADDR, calibData[7]); + write8(GYRO_OFFSET_Y_LSB_ADDR, calibData[8]); + write8(GYRO_OFFSET_Y_MSB_ADDR, calibData[9]); + write8(GYRO_OFFSET_Z_LSB_ADDR, calibData[10]); + write8(GYRO_OFFSET_Z_MSB_ADDR, calibData[11]); + + write8(MAG_OFFSET_X_LSB_ADDR, calibData[12]); + write8(MAG_OFFSET_X_MSB_ADDR, calibData[13]); + write8(MAG_OFFSET_Y_LSB_ADDR, calibData[14]); + write8(MAG_OFFSET_Y_MSB_ADDR, calibData[15]); + write8(MAG_OFFSET_Z_LSB_ADDR, calibData[16]); + write8(MAG_OFFSET_Z_MSB_ADDR, calibData[17]); + + write8(ACCEL_RADIUS_LSB_ADDR, calibData[18]); + write8(ACCEL_RADIUS_MSB_ADDR, calibData[19]); + + write8(MAG_RADIUS_LSB_ADDR, calibData[20]); + write8(MAG_RADIUS_MSB_ADDR, calibData[21]); + + setMode(lastMode); +} + +/**************************************************************************/ +/*! + @brief Writes to the sensor's offset registers from an offset struct + */ +/**************************************************************************/ +void Adafruit_BNO055::setSensorOffsets(const adafruit_bno055_offsets_t &offsets_type) +{ + adafruit_bno055_opmode_t lastMode = _aMode; + setMode(OPERATION_MODE_CONFIG); + delay(25); + + write8(ACCEL_OFFSET_X_LSB_ADDR, (offsets_type.accel_offset_x) & 0x0FF); + write8(ACCEL_OFFSET_X_MSB_ADDR, (offsets_type.accel_offset_x >> 8) & 0x0FF); + write8(ACCEL_OFFSET_Y_LSB_ADDR, (offsets_type.accel_offset_y) & 0x0FF); + write8(ACCEL_OFFSET_Y_MSB_ADDR, (offsets_type.accel_offset_y >> 8) & 0x0FF); + write8(ACCEL_OFFSET_Z_LSB_ADDR, (offsets_type.accel_offset_z) & 0x0FF); + write8(ACCEL_OFFSET_Z_MSB_ADDR, (offsets_type.accel_offset_z >> 8) & 0x0FF); + + write8(GYRO_OFFSET_X_LSB_ADDR, (offsets_type.gyro_offset_x) & 0x0FF); + write8(GYRO_OFFSET_X_MSB_ADDR, (offsets_type.gyro_offset_x >> 8) & 0x0FF); + write8(GYRO_OFFSET_Y_LSB_ADDR, (offsets_type.gyro_offset_y) & 0x0FF); + write8(GYRO_OFFSET_Y_MSB_ADDR, (offsets_type.gyro_offset_y >> 8) & 0x0FF); + write8(GYRO_OFFSET_Z_LSB_ADDR, (offsets_type.gyro_offset_z) & 0x0FF); + write8(GYRO_OFFSET_Z_MSB_ADDR, (offsets_type.gyro_offset_z >> 8) & 0x0FF); + + write8(MAG_OFFSET_X_LSB_ADDR, (offsets_type.mag_offset_x) & 0x0FF); + write8(MAG_OFFSET_X_MSB_ADDR, (offsets_type.mag_offset_x >> 8) & 0x0FF); + write8(MAG_OFFSET_Y_LSB_ADDR, (offsets_type.mag_offset_y) & 0x0FF); + write8(MAG_OFFSET_Y_MSB_ADDR, (offsets_type.mag_offset_y >> 8) & 0x0FF); + write8(MAG_OFFSET_Z_LSB_ADDR, (offsets_type.mag_offset_z) & 0x0FF); + write8(MAG_OFFSET_Z_MSB_ADDR, (offsets_type.mag_offset_z >> 8) & 0x0FF); + + write8(ACCEL_RADIUS_LSB_ADDR, (offsets_type.accel_radius) & 0x0FF); + write8(ACCEL_RADIUS_MSB_ADDR, (offsets_type.accel_radius >> 8) & 0x0FF); + + write8(MAG_RADIUS_LSB_ADDR, (offsets_type.mag_radius) & 0x0FF); + write8(MAG_RADIUS_MSB_ADDR, (offsets_type.mag_radius >> 8) & 0x0FF); + + setMode(lastMode); +} + +bool Adafruit_BNO055::isFullyCalibrated(void) +{ + uint8_t system, gyro, accel, mag; + getCalibration(&system, &gyro, &accel, &mag); + if (system < 3 || gyro < 3 || accel < 3 || mag < 3) + return false; + return true; +} + + +/*************************************************************************** + PRIVATE FUNCTIONS + ***************************************************************************/ + +/**************************************************************************/ +/*! + @brief Writes an 8 bit value over I2C + */ +/**************************************************************************/ +bool Adafruit_BNO055::write8(adafruit_bno055_reg_t reg, byte value) +{ + if (_iBus == WIRE_BUS) + { + Wire.beginTransmission(_aAddress); //// MODIFIED RB +#if ARDUINO >= 100 + Wire.write((uint8_t)reg); /// TO BE MODIFIED? NO + Wire.write((uint8_t)value); /// TO BE MODIFIED? NO +#else + Wire.send(reg); /// TO BE MODIFIED? NO + Wire.send(value); /// TO BE MODIFIED? NO +#endif + Wire.endTransmission(); /// TO BE MODIFIED? NO + + /* ToDo: Check for error! */ + return true; + } + else + { + Wire1.beginTransmission(_aAddress); //// MODIFIED RB +#if ARDUINO >= 100 + Wire1.write((uint8_t)reg); /// TO BE MODIFIED? NO + Wire1.write((uint8_t)value); /// TO BE MODIFIED? NO +#else + Wire1.send(reg); /// TO BE MODIFIED? NO + Wire1.send(value); /// TO BE MODIFIED? NO +#endif + Wire1.endTransmission(); /// TO BE MODIFIED? NO + + /* ToDo: Check for error! */ + return true; + } +} + +/**************************************************************************/ +/*! + @brief Reads an 8 bit value over I2C + */ +/**************************************************************************/ +byte Adafruit_BNO055::read8(adafruit_bno055_reg_t reg ) +{ + byte value = 0; + + if (_iBus == WIRE_BUS) + { + Wire.beginTransmission(_aAddress); /// TO BE MODIFIED? NO +#if ARDUINO >= 100 + Wire.write((uint8_t)reg); /// TO BE MODIFIED? NO +#else + Wire.send(reg); +#endif + Wire.endTransmission(); + Wire.requestFrom(_aAddress, (byte)1); /// TO BE MODIFIED? NO +#if ARDUINO >= 100 + value = Wire.read(); /// TO BE MODIFIED? NO +#else + value = Wire.receive(); //// MODIFIED RB receive -> readByte + //value = Wire.readByte(); //// MODIFIED RB receive -> readByte +#endif + + return value; + } + else + { + Wire1.beginTransmission(_aAddress); /// TO BE MODIFIED? NO +#if ARDUINO >= 100 + Wire1.write((uint8_t)reg); /// TO BE MODIFIED? NO +#else + Wire1.send(reg); +#endif + Wire1.endTransmission(); + Wire1.requestFrom(_aAddress, (byte)1); /// TO BE MODIFIED? NO +#if ARDUINO >= 100 + value = Wire1.read(); /// TO BE MODIFIED? NO +#else + value = Wire1.readByte(); //// MODIFIED RB receive -> readByte +#endif + + return value; + } +} + +/**************************************************************************/ +/*! + @brief Reads the specified number of bytes over I2C + */ +/**************************************************************************/ +bool Adafruit_BNO055::readLen(adafruit_bno055_reg_t reg, byte * buffer, uint8_t len) +{ + if (_iBus == WIRE_BUS) + { + Wire.beginTransmission(_aAddress); /// TO BE MODIFIED? NO +#if ARDUINO >= 100 + Wire.write((uint8_t)reg); /// TO BE MODIFIED? NO +#else + Wire.send(reg); /// TO BE MODIFIED? NO +#endif + Wire.endTransmission(); + Wire.requestFrom(_aAddress, (byte)len); /// TO BE MODIFIED? NO + + for (uint8_t i = 0; i < len; i++) + { +#if ARDUINO >= 100 + buffer[i] = Wire.read(); /// TO BE MODIFIED? NO +#else + buffer[i] = Wire.readByte(); //// MODIFIE RB receive -> readByte +#endif + } + + /* ToDo: Check for errors! */ + return true; + } + else + { + Wire1.beginTransmission(_aAddress); /// TO BE MODIFIED? NO +#if ARDUINO >= 100 + Wire1.write((uint8_t)reg); /// TO BE MODIFIED? NO +#else + Wire1.send(reg); /// TO BE MODIFIED? NO +#endif + Wire1.endTransmission(); + Wire1.requestFrom(_aAddress, (byte)len); /// TO BE MODIFIED? NO + + for (uint8_t i = 0; i < len; i++) + { +#if ARDUINO >= 100 + buffer[i] = Wire1.read(); /// TO BE MODIFIED? NO +#else + buffer[i] = Wire1.readByte(); //// MODIFIE RB receive -> readByte +#endif + } + + /* ToDo: Check for errors! */ + return true; + } + +} \ No newline at end of file diff --git a/software/firmware/libraries/Adafruit_BNO055_t3/Adafruit_BNO055_t3.h b/software/firmware/libraries/Adafruit_BNO055_t3/Adafruit_BNO055_t3.h new file mode 100644 index 0000000..dee043b --- /dev/null +++ b/software/firmware/libraries/Adafruit_BNO055_t3/Adafruit_BNO055_t3.h @@ -0,0 +1,344 @@ +/*************************************************************************** + This is a library for the BNO055 orientation sensor + + Designed specifically to work with the Adafruit BNO055 Breakout. + + Pick one up today in the adafruit shop! + ------> http://www.adafruit.com/products + + These sensors use I2C to communicate, 2 pins are required to interface. + + Adafruit invests time and resources providing this open source code, + please support Adafruit andopen-source hardware by purchasing products + from Adafruit! + + Written by KTOWN for Adafruit Industries. + + !!!!!MODIFIED VERSION TO USE I2C_T3 LIBRARY FOR TEENSY INSTEAD OF WIRE + IN ORDER TO USE TEENSY'S BOTH I2C PORTS + Roald Baudoux - 2016-03 + + Updated 2016-03-15: i2c_bus type defined to set choice of Wire or Wire1 + + MIT license, all text above must be included in any redistribution + ***************************************************************************/ + +#ifndef __ADAFRUIT_BNO055_H__ +#define __ADAFRUIT_BNO055_H__ + +#if (ARDUINO >= 100) +#include "Arduino.h" +#else +#include "WProgram.h" +#endif + +// code for AT_TINY85 deleted (no AT_TINY85 on Teensy boards) +#include // MODIFIED FROM Wire.h to i2c_t3.h + + +#include +#include + +#define BNO055_ADDRESS_A (0x28) +#define BNO055_ADDRESS_B (0x29) +#define BNO055_ID (0xA0) + +#define NUM_BNO055_OFFSET_REGISTERS (22) + +enum i2c_bus {WIRE_BUS, WIRE1_BUS}; // ADDED RB + +typedef struct +{ + uint16_t accel_offset_x; + uint16_t accel_offset_y; + uint16_t accel_offset_z; + uint16_t gyro_offset_x; + uint16_t gyro_offset_y; + uint16_t gyro_offset_z; + uint16_t mag_offset_x; + uint16_t mag_offset_y; + uint16_t mag_offset_z; + + uint16_t accel_radius; + uint16_t mag_radius; +} adafruit_bno055_offsets_t; + +class Adafruit_BNO055 : public Adafruit_Sensor +{ +public: + typedef enum + { + /* Page id register definition */ + BNO055_PAGE_ID_ADDR = 0X07, + + /* PAGE0 REGISTER DEFINITION START*/ + BNO055_CHIP_ID_ADDR = 0x00, + BNO055_ACCEL_REV_ID_ADDR = 0x01, + BNO055_MAG_REV_ID_ADDR = 0x02, + BNO055_GYRO_REV_ID_ADDR = 0x03, + BNO055_SW_REV_ID_LSB_ADDR = 0x04, + BNO055_SW_REV_ID_MSB_ADDR = 0x05, + BNO055_BL_REV_ID_ADDR = 0X06, + + /* Accel data register */ + BNO055_ACCEL_DATA_X_LSB_ADDR = 0X08, + BNO055_ACCEL_DATA_X_MSB_ADDR = 0X09, + BNO055_ACCEL_DATA_Y_LSB_ADDR = 0X0A, + BNO055_ACCEL_DATA_Y_MSB_ADDR = 0X0B, + BNO055_ACCEL_DATA_Z_LSB_ADDR = 0X0C, + BNO055_ACCEL_DATA_Z_MSB_ADDR = 0X0D, + + /* Mag data register */ + BNO055_MAG_DATA_X_LSB_ADDR = 0X0E, + BNO055_MAG_DATA_X_MSB_ADDR = 0X0F, + BNO055_MAG_DATA_Y_LSB_ADDR = 0X10, + BNO055_MAG_DATA_Y_MSB_ADDR = 0X11, + BNO055_MAG_DATA_Z_LSB_ADDR = 0X12, + BNO055_MAG_DATA_Z_MSB_ADDR = 0X13, + + /* Gyro data registers */ + BNO055_GYRO_DATA_X_LSB_ADDR = 0X14, + BNO055_GYRO_DATA_X_MSB_ADDR = 0X15, + BNO055_GYRO_DATA_Y_LSB_ADDR = 0X16, + BNO055_GYRO_DATA_Y_MSB_ADDR = 0X17, + BNO055_GYRO_DATA_Z_LSB_ADDR = 0X18, + BNO055_GYRO_DATA_Z_MSB_ADDR = 0X19, + + /* Euler data registers */ + BNO055_EULER_H_LSB_ADDR = 0X1A, + BNO055_EULER_H_MSB_ADDR = 0X1B, + BNO055_EULER_R_LSB_ADDR = 0X1C, + BNO055_EULER_R_MSB_ADDR = 0X1D, + BNO055_EULER_P_LSB_ADDR = 0X1E, + BNO055_EULER_P_MSB_ADDR = 0X1F, + + /* Quaternion data registers */ + BNO055_QUATERNION_DATA_W_LSB_ADDR = 0X20, + BNO055_QUATERNION_DATA_W_MSB_ADDR = 0X21, + BNO055_QUATERNION_DATA_X_LSB_ADDR = 0X22, + BNO055_QUATERNION_DATA_X_MSB_ADDR = 0X23, + BNO055_QUATERNION_DATA_Y_LSB_ADDR = 0X24, + BNO055_QUATERNION_DATA_Y_MSB_ADDR = 0X25, + BNO055_QUATERNION_DATA_Z_LSB_ADDR = 0X26, + BNO055_QUATERNION_DATA_Z_MSB_ADDR = 0X27, + + /* Linear acceleration data registers */ + BNO055_LINEAR_ACCEL_DATA_X_LSB_ADDR = 0X28, + BNO055_LINEAR_ACCEL_DATA_X_MSB_ADDR = 0X29, + BNO055_LINEAR_ACCEL_DATA_Y_LSB_ADDR = 0X2A, + BNO055_LINEAR_ACCEL_DATA_Y_MSB_ADDR = 0X2B, + BNO055_LINEAR_ACCEL_DATA_Z_LSB_ADDR = 0X2C, + BNO055_LINEAR_ACCEL_DATA_Z_MSB_ADDR = 0X2D, + + /* Gravity data registers */ + BNO055_GRAVITY_DATA_X_LSB_ADDR = 0X2E, + BNO055_GRAVITY_DATA_X_MSB_ADDR = 0X2F, + BNO055_GRAVITY_DATA_Y_LSB_ADDR = 0X30, + BNO055_GRAVITY_DATA_Y_MSB_ADDR = 0X31, + BNO055_GRAVITY_DATA_Z_LSB_ADDR = 0X32, + BNO055_GRAVITY_DATA_Z_MSB_ADDR = 0X33, + + /* Temperature data register */ + BNO055_TEMP_ADDR = 0X34, + + /* Status registers */ + BNO055_CALIB_STAT_ADDR = 0X35, + BNO055_SELFTEST_RESULT_ADDR = 0X36, + BNO055_INTR_STAT_ADDR = 0X37, + + BNO055_SYS_CLK_STAT_ADDR = 0X38, + BNO055_SYS_STAT_ADDR = 0X39, + BNO055_SYS_ERR_ADDR = 0X3A, + + /* Unit selection register */ + BNO055_UNIT_SEL_ADDR = 0X3B, + BNO055_DATA_SELECT_ADDR = 0X3C, + + /* Mode registers */ + BNO055_OPR_MODE_ADDR = 0X3D, + BNO055_PWR_MODE_ADDR = 0X3E, + + BNO055_SYS_TRIGGER_ADDR = 0X3F, + BNO055_TEMP_SOURCE_ADDR = 0X40, + + /* Axis remap registers */ + BNO055_AXIS_MAP_CONFIG_ADDR = 0X41, + BNO055_AXIS_MAP_SIGN_ADDR = 0X42, + + /* SIC registers */ + BNO055_SIC_MATRIX_0_LSB_ADDR = 0X43, + BNO055_SIC_MATRIX_0_MSB_ADDR = 0X44, + BNO055_SIC_MATRIX_1_LSB_ADDR = 0X45, + BNO055_SIC_MATRIX_1_MSB_ADDR = 0X46, + BNO055_SIC_MATRIX_2_LSB_ADDR = 0X47, + BNO055_SIC_MATRIX_2_MSB_ADDR = 0X48, + BNO055_SIC_MATRIX_3_LSB_ADDR = 0X49, + BNO055_SIC_MATRIX_3_MSB_ADDR = 0X4A, + BNO055_SIC_MATRIX_4_LSB_ADDR = 0X4B, + BNO055_SIC_MATRIX_4_MSB_ADDR = 0X4C, + BNO055_SIC_MATRIX_5_LSB_ADDR = 0X4D, + BNO055_SIC_MATRIX_5_MSB_ADDR = 0X4E, + BNO055_SIC_MATRIX_6_LSB_ADDR = 0X4F, + BNO055_SIC_MATRIX_6_MSB_ADDR = 0X50, + BNO055_SIC_MATRIX_7_LSB_ADDR = 0X51, + BNO055_SIC_MATRIX_7_MSB_ADDR = 0X52, + BNO055_SIC_MATRIX_8_LSB_ADDR = 0X53, + BNO055_SIC_MATRIX_8_MSB_ADDR = 0X54, + + /* Accelerometer Offset registers */ + ACCEL_OFFSET_X_LSB_ADDR = 0X55, + ACCEL_OFFSET_X_MSB_ADDR = 0X56, + ACCEL_OFFSET_Y_LSB_ADDR = 0X57, + ACCEL_OFFSET_Y_MSB_ADDR = 0X58, + ACCEL_OFFSET_Z_LSB_ADDR = 0X59, + ACCEL_OFFSET_Z_MSB_ADDR = 0X5A, + + /* Magnetometer Offset registers */ + MAG_OFFSET_X_LSB_ADDR = 0X5B, + MAG_OFFSET_X_MSB_ADDR = 0X5C, + MAG_OFFSET_Y_LSB_ADDR = 0X5D, + MAG_OFFSET_Y_MSB_ADDR = 0X5E, + MAG_OFFSET_Z_LSB_ADDR = 0X5F, + MAG_OFFSET_Z_MSB_ADDR = 0X60, + + /* Gyroscope Offset register s*/ + GYRO_OFFSET_X_LSB_ADDR = 0X61, + GYRO_OFFSET_X_MSB_ADDR = 0X62, + GYRO_OFFSET_Y_LSB_ADDR = 0X63, + GYRO_OFFSET_Y_MSB_ADDR = 0X64, + GYRO_OFFSET_Z_LSB_ADDR = 0X65, + GYRO_OFFSET_Z_MSB_ADDR = 0X66, + + /* Radius registers */ + ACCEL_RADIUS_LSB_ADDR = 0X67, + ACCEL_RADIUS_MSB_ADDR = 0X68, + MAG_RADIUS_LSB_ADDR = 0X69, + MAG_RADIUS_MSB_ADDR = 0X6A + } adafruit_bno055_reg_t; + + typedef enum + { + POWER_MODE_NORMAL = 0X00, + POWER_MODE_LOWPOWER = 0X01, + POWER_MODE_SUSPEND = 0X02 + } adafruit_bno055_powermode_t; + + typedef enum + { + /* Operation mode settings*/ + OPERATION_MODE_CONFIG = 0X00, + OPERATION_MODE_ACCONLY = 0X01, + OPERATION_MODE_MAGONLY = 0X02, + OPERATION_MODE_GYRONLY = 0X03, + OPERATION_MODE_ACCMAG = 0X04, + OPERATION_MODE_ACCGYRO = 0X05, + OPERATION_MODE_MAGGYRO = 0X06, + OPERATION_MODE_AMG = 0X07, + OPERATION_MODE_IMUPLUS = 0X08, + OPERATION_MODE_COMPASS = 0X09, + OPERATION_MODE_M4G = 0X0A, + OPERATION_MODE_NDOF_FMC_OFF = 0X0B, + OPERATION_MODE_NDOF = 0X0C + } adafruit_bno055_opmode_t; + + typedef enum + { + REMAP_CONFIG_P0 = 0x21, + REMAP_CONFIG_P1 = 0x24, // default + REMAP_CONFIG_P2 = 0x24, + REMAP_CONFIG_P3 = 0x21, + REMAP_CONFIG_P4 = 0x24, + REMAP_CONFIG_P5 = 0x21, + REMAP_CONFIG_P6 = 0x21, + REMAP_CONFIG_P7 = 0x24 + } adafruit_bno055_axis_remap_config_t; + + typedef enum + { + REMAP_SIGN_P0 = 0x04, + REMAP_SIGN_P1 = 0x00, // default + REMAP_SIGN_P2 = 0x06, + REMAP_SIGN_P3 = 0x02, + REMAP_SIGN_P4 = 0x03, + REMAP_SIGN_P5 = 0x01, + REMAP_SIGN_P6 = 0x07, + REMAP_SIGN_P7 = 0x05 + } adafruit_bno055_axis_remap_sign_t; + + typedef struct + { + uint8_t accel_rev; + uint8_t mag_rev; + uint8_t gyro_rev; + uint16_t sw_rev; + uint8_t bl_rev; + } adafruit_bno055_rev_info_t; + + typedef enum + { + VECTOR_ACCELEROMETER = BNO055_ACCEL_DATA_X_LSB_ADDR, + VECTOR_MAGNETOMETER = BNO055_MAG_DATA_X_LSB_ADDR, + VECTOR_GYROSCOPE = BNO055_GYRO_DATA_X_LSB_ADDR, + VECTOR_EULER = BNO055_EULER_H_LSB_ADDR, + VECTOR_LINEARACCEL = BNO055_LINEAR_ACCEL_DATA_X_LSB_ADDR, + VECTOR_GRAVITY = BNO055_GRAVITY_DATA_X_LSB_ADDR + } adafruit_vector_type_t; + + // Arduino Zero board check removed (No Zero in Teensy range) + /* + #ifdef ARDUINO_SAMD_ZERO + #error "On an arduino Zero, BNO055's ADR pin must be high. Fix that, then delete this line." + Adafruit_BNO055 ( int32_t sensorID = -1, uint8_t address = BNO055_ADDRESS_B ); + #else + Adafruit_BNO055 ( int32_t sensorID = -1, uint8_t address = BNO055_ADDRESS_A ); + #endif + */ + + Adafruit_BNO055 (i2c_bus iBus = WIRE_BUS, int32_t sensorID = -1, uint8_t aAddress = BNO055_ADDRESS_A, i2c_mode iMode = I2C_MASTER, i2c_pins pins = I2C_PINS_18_19, i2c_pullup pullup = I2C_PULLUP_INT, i2c_rate iRate = I2C_RATE_100, i2c_op_mode opeMode = I2C_OP_MODE_ISR); // MODIFIED + + bool begin ( adafruit_bno055_opmode_t aMode = OPERATION_MODE_NDOF ); + void setMode ( adafruit_bno055_opmode_t aMode ); + void getRevInfo ( adafruit_bno055_rev_info_t* ); + void displayRevInfo ( void ); + void setExtCrystalUse ( boolean usextal ); + void getSystemStatus ( uint8_t *system_status, + uint8_t *self_test_result, + uint8_t *system_error); + void displaySystemStatus ( void ); + void getCalibration ( uint8_t* system, uint8_t* gyro, uint8_t* accel, uint8_t* mag); + + imu::Vector<3> getVector ( adafruit_vector_type_t vector_type ); + imu::Quaternion getQuat ( void ); + int8_t getTemp ( void ); + + /* Adafruit_Sensor implementation */ + bool getEvent ( sensors_event_t* ); + void getSensor ( sensor_t* ); + + /* Functions to deal with raw calibration data */ + bool getSensorOffsets(uint8_t* calibData); + bool getSensorOffsets(adafruit_bno055_offsets_t &offsets_type); + void setSensorOffsets(const uint8_t* calibData); + void setSensorOffsets(const adafruit_bno055_offsets_t &offsets_type); + bool isFullyCalibrated(void); + +private: + byte read8 ( adafruit_bno055_reg_t ); + bool readLen ( adafruit_bno055_reg_t, byte* buffer, uint8_t len ); + bool write8 ( adafruit_bno055_reg_t, byte value ); + + + // bool _i2cBus; // ADDED : O for Wire and 1 for Wire1 + uint8_t _aAddress; + int32_t _sensorID; + adafruit_bno055_opmode_t _aMode; + // ADDED RB : + i2c_bus _iBus; // Wire or Wire 1 + i2c_mode _iMode; // MASTER OR SLAVE MODE + i2c_pins _pins; + i2c_pullup _pullup; + i2c_rate _iRate; + i2c_op_mode _opeMode; +}; + +#endif diff --git a/software/firmware/libraries/Adafruit_BNO055_t3/utility/imumaths.h b/software/firmware/libraries/Adafruit_BNO055_t3/utility/imumaths.h new file mode 100644 index 0000000..70d15fd --- /dev/null +++ b/software/firmware/libraries/Adafruit_BNO055_t3/utility/imumaths.h @@ -0,0 +1,30 @@ +/* + Inertial Measurement Unit Maths Library + Copyright (C) 2013-2014 Samuel Cowen + www.camelsoftware.com + + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . +*/ + +#ifndef IMUMATH_H +#define IMUMATH_H + + +#include "vector.h" +#include "matrix.h" +#include "quaternion.h" + + +#endif + diff --git a/software/firmware/libraries/Adafruit_BNO055_t3/utility/matrix.h b/software/firmware/libraries/Adafruit_BNO055_t3/utility/matrix.h new file mode 100644 index 0000000..6fa4b1a --- /dev/null +++ b/software/firmware/libraries/Adafruit_BNO055_t3/utility/matrix.h @@ -0,0 +1,243 @@ +/* + Inertial Measurement Unit Maths Library + Copyright (C) 2013-2014 Samuel Cowen + www.camelsoftware.com + + Bug fixes and cleanups by Gé Vissers (gvissers@gmail.com) + + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . +*/ + +#ifndef IMUMATH_MATRIX_HPP +#define IMUMATH_MATRIX_HPP + +#include +#include + +#include "vector.h" + +namespace imu +{ + + +template class Matrix +{ +public: + Matrix() + { + memset(_cell_data, 0, N*N*sizeof(double)); + } + + Matrix(const Matrix &m) + { + for (int ij = 0; ij < N*N; ++ij) + { + _cell_data[ij] = m._cell_data[ij]; + } + } + + ~Matrix() + { + } + + Matrix& operator=(const Matrix& m) + { + for (int ij = 0; ij < N*N; ++ij) + { + _cell_data[ij] = m._cell_data[ij]; + } + return *this; + } + + Vector row_to_vector(int i) const + { + Vector ret; + for (int j = 0; j < N; j++) + { + ret[j] = cell(i, j); + } + return ret; + } + + Vector col_to_vector(int j) const + { + Vector ret; + for (int i = 0; i < N; i++) + { + ret[i] = cell(i, j); + } + return ret; + } + + void vector_to_row(const Vector& v, int i) + { + for (int j = 0; j < N; j++) + { + cell(i, j) = v[j]; + } + } + + void vector_to_col(const Vector& v, int j) + { + for (int i = 0; i < N; i++) + { + cell(i, j) = v[i]; + } + } + + double operator()(int i, int j) const + { + return cell(i, j); + } + double& operator()(int i, int j) + { + return cell(i, j); + } + + double cell(int i, int j) const + { + return _cell_data[i*N+j]; + } + double& cell(int i, int j) + { + return _cell_data[i*N+j]; + } + + + Matrix operator+(const Matrix& m) const + { + Matrix ret; + for (int ij = 0; ij < N*N; ++ij) + { + ret._cell_data[ij] = _cell_data[ij] + m._cell_data[ij]; + } + return ret; + } + + Matrix operator-(const Matrix& m) const + { + Matrix ret; + for (int ij = 0; ij < N*N; ++ij) + { + ret._cell_data[ij] = _cell_data[ij] - m._cell_data[ij]; + } + return ret; + } + + Matrix operator*(double scalar) const + { + Matrix ret; + for (int ij = 0; ij < N*N; ++ij) + { + ret._cell_data[ij] = _cell_data[ij] * scalar; + } + return ret; + } + + Matrix operator*(const Matrix& m) const + { + Matrix ret; + for (int i = 0; i < N; i++) + { + Vector row = row_to_vector(i); + for (int j = 0; j < N; j++) + { + ret(i, j) = row.dot(m.col_to_vector(j)); + } + } + return ret; + } + + Matrix transpose() const + { + Matrix ret; + for (int i = 0; i < N; i++) + { + for (int j = 0; j < N; j++) + { + ret(j, i) = cell(i, j); + } + } + return ret; + } + + Matrix minor_matrix(int row, int col) const + { + Matrix ret; + for (int i = 0, im = 0; i < N; i++) + { + if (i == row) + continue; + + for (int j = 0, jm = 0; j < N; j++) + { + if (j != col) + { + ret(im, jm++) = cell(i, j); + } + } + im++; + } + return ret; + } + + double determinant() const + { + // specialization for N == 1 given below this class + double det = 0.0, sign = 1.0; + for (int i = 0; i < N; ++i, sign = -sign) + det += sign * cell(0, i) * minor_matrix(0, i).determinant(); + return det; + } + + Matrix invert() const + { + Matrix ret; + double det = determinant(); + + for (int i = 0; i < N; i++) + { + for (int j = 0; j < N; j++) + { + ret(i, j) = minor_matrix(j, i).determinant() / det; + if ((i+j)%2 == 1) + ret(i, j) = -ret(i, j); + } + } + return ret; + } + + double trace() const + { + double tr = 0.0; + for (int i = 0; i < N; ++i) + tr += cell(i, i); + return tr; + } + +private: + double _cell_data[N*N]; +}; + + +template<> +inline double Matrix<1>::determinant() const +{ + return cell(0, 0); +} + +}; + +#endif + diff --git a/software/firmware/libraries/Adafruit_BNO055_t3/utility/quaternion.h b/software/firmware/libraries/Adafruit_BNO055_t3/utility/quaternion.h new file mode 100644 index 0000000..d433f66 --- /dev/null +++ b/software/firmware/libraries/Adafruit_BNO055_t3/utility/quaternion.h @@ -0,0 +1,272 @@ +/* + Inertial Measurement Unit Maths Library + Copyright (C) 2013-2014 Samuel Cowen + www.camelsoftware.com + + Bug fixes and cleanups by Gé Vissers (gvissers@gmail.com) + + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . +*/ + + +#ifndef IMUMATH_QUATERNION_HPP +#define IMUMATH_QUATERNION_HPP + +#include +#include +#include +#include + +#include "matrix.h" + + +namespace imu +{ + +class Quaternion +{ +public: + Quaternion(): _w(1.0), _x(0.0), _y(0.0), _z(0.0) {} + + Quaternion(double w, double x, double y, double z): + _w(w), _x(x), _y(y), _z(z) {} + + Quaternion(double w, Vector<3> vec): + _w(w), _x(vec.x()), _y(vec.y()), _z(vec.z()) {} + + double& w() + { + return _w; + } + double& x() + { + return _x; + } + double& y() + { + return _y; + } + double& z() + { + return _z; + } + + double w() const + { + return _w; + } + double x() const + { + return _x; + } + double y() const + { + return _y; + } + double z() const + { + return _z; + } + + double magnitude() const + { + return sqrt(_w*_w + _x*_x + _y*_y + _z*_z); + } + + void normalize() + { + double mag = magnitude(); + *this = this->scale(1/mag); + } + + Quaternion conjugate() const + { + return Quaternion(_w, -_x, -_y, -_z); + } + + void fromAxisAngle(const Vector<3>& axis, double theta) + { + _w = cos(theta/2); + //only need to calculate sine of half theta once + double sht = sin(theta/2); + _x = axis.x() * sht; + _y = axis.y() * sht; + _z = axis.z() * sht; + } + + void fromMatrix(const Matrix<3>& m) + { + double tr = m.trace(); + + double S; + if (tr > 0) + { + S = sqrt(tr+1.0) * 2; + _w = 0.25 * S; + _x = (m(2, 1) - m(1, 2)) / S; + _y = (m(0, 2) - m(2, 0)) / S; + _z = (m(1, 0) - m(0, 1)) / S; + } + else if (m(0, 0) > m(1, 1) && m(0, 0) > m(2, 2)) + { + S = sqrt(1.0 + m(0, 0) - m(1, 1) - m(2, 2)) * 2; + _w = (m(2, 1) - m(1, 2)) / S; + _x = 0.25 * S; + _y = (m(0, 1) + m(1, 0)) / S; + _z = (m(0, 2) + m(2, 0)) / S; + } + else if (m(1, 1) > m(2, 2)) + { + S = sqrt(1.0 + m(1, 1) - m(0, 0) - m(2, 2)) * 2; + _w = (m(0, 2) - m(2, 0)) / S; + _x = (m(0, 1) + m(1, 0)) / S; + _y = 0.25 * S; + _z = (m(1, 2) + m(2, 1)) / S; + } + else + { + S = sqrt(1.0 + m(2, 2) - m(0, 0) - m(1, 1)) * 2; + _w = (m(1, 0) - m(0, 1)) / S; + _x = (m(0, 2) + m(2, 0)) / S; + _y = (m(1, 2) + m(2, 1)) / S; + _z = 0.25 * S; + } + } + + void toAxisAngle(Vector<3>& axis, double& angle) const + { + double sqw = sqrt(1-_w*_w); + if (sqw == 0) //it's a singularity and divide by zero, avoid + return; + + angle = 2 * acos(_w); + axis.x() = _x / sqw; + axis.y() = _y / sqw; + axis.z() = _z / sqw; + } + + Matrix<3> toMatrix() const + { + Matrix<3> ret; + ret.cell(0, 0) = 1 - 2*_y*_y - 2*_z*_z; + ret.cell(0, 1) = 2*_x*_y - 2*_w*_z; + ret.cell(0, 2) = 2*_x*_z + 2*_w*_y; + + ret.cell(1, 0) = 2*_x*_y + 2*_w*_z; + ret.cell(1, 1) = 1 - 2*_x*_x - 2*_z*_z; + ret.cell(1, 2) = 2*_y*_z - 2*_w*_x; + + ret.cell(2, 0) = 2*_x*_z - 2*_w*_y; + ret.cell(2, 1) = 2*_y*_z + 2*_w*_x; + ret.cell(2, 2) = 1 - 2*_x*_x - 2*_y*_y; + return ret; + } + + + // Returns euler angles that represent the quaternion. Angles are + // returned in rotation order and right-handed about the specified + // axes: + // + // v[0] is applied 1st about z (ie, roll) + // v[1] is applied 2nd about y (ie, pitch) + // v[2] is applied 3rd about x (ie, yaw) + // + // Note that this means result.x() is not a rotation about x; + // similarly for result.z(). + // + Vector<3> toEuler() const + { + Vector<3> ret; + double sqw = _w*_w; + double sqx = _x*_x; + double sqy = _y*_y; + double sqz = _z*_z; + + ret.x() = atan2(2.0*(_x*_y+_z*_w),(sqx-sqy-sqz+sqw)); + ret.y() = asin(-2.0*(_x*_z-_y*_w)/(sqx+sqy+sqz+sqw)); + ret.z() = atan2(2.0*(_y*_z+_x*_w),(-sqx-sqy+sqz+sqw)); + + return ret; + } + + Vector<3> toAngularVelocity(double dt) const + { + Vector<3> ret; + Quaternion one(1.0, 0.0, 0.0, 0.0); + Quaternion delta = one - *this; + Quaternion r = (delta/dt); + r = r * 2; + r = r * one; + + ret.x() = r.x(); + ret.y() = r.y(); + ret.z() = r.z(); + return ret; + } + + Vector<3> rotateVector(const Vector<2>& v) const + { + return rotateVector(Vector<3>(v.x(), v.y())); + } + + Vector<3> rotateVector(const Vector<3>& v) const + { + Vector<3> qv(_x, _y, _z); + Vector<3> t = qv.cross(v) * 2.0; + return v + t*_w + qv.cross(t); + } + + + Quaternion operator*(const Quaternion& q) const + { + return Quaternion( + _w*q._w - _x*q._x - _y*q._y - _z*q._z, + _w*q._x + _x*q._w + _y*q._z - _z*q._y, + _w*q._y - _x*q._z + _y*q._w + _z*q._x, + _w*q._z + _x*q._y - _y*q._x + _z*q._w + ); + } + + Quaternion operator+(const Quaternion& q) const + { + return Quaternion(_w + q._w, _x + q._x, _y + q._y, _z + q._z); + } + + Quaternion operator-(const Quaternion& q) const + { + return Quaternion(_w - q._w, _x - q._x, _y - q._y, _z - q._z); + } + + Quaternion operator/(double scalar) const + { + return Quaternion(_w / scalar, _x / scalar, _y / scalar, _z / scalar); + } + + Quaternion operator*(double scalar) const + { + return scale(scalar); + } + + Quaternion scale(double scalar) const + { + return Quaternion(_w * scalar, _x * scalar, _y * scalar, _z * scalar); + } + +private: + double _w, _x, _y, _z; +}; + +} // namespace + +#endif diff --git a/software/firmware/libraries/Adafruit_BNO055_t3/utility/vector.h b/software/firmware/libraries/Adafruit_BNO055_t3/utility/vector.h new file mode 100644 index 0000000..a5741d5 --- /dev/null +++ b/software/firmware/libraries/Adafruit_BNO055_t3/utility/vector.h @@ -0,0 +1,227 @@ +/* + Inertial Measurement Unit Maths Library + Copyright (C) 2013-2014 Samuel Cowen + www.camelsoftware.com + + Bug fixes and cleanups by Gé Vissers (gvissers@gmail.com) + + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . +*/ + +#ifndef IMUMATH_VECTOR_HPP +#define IMUMATH_VECTOR_HPP + +#include +#include +#include + + +namespace imu +{ + +template class Vector +{ +public: + Vector() + { + memset(p_vec, 0, sizeof(double)*N); + } + + Vector(double a) + { + memset(p_vec, 0, sizeof(double)*N); + p_vec[0] = a; + } + + Vector(double a, double b) + { + memset(p_vec, 0, sizeof(double)*N); + p_vec[0] = a; + p_vec[1] = b; + } + + Vector(double a, double b, double c) + { + memset(p_vec, 0, sizeof(double)*N); + p_vec[0] = a; + p_vec[1] = b; + p_vec[2] = c; + } + + Vector(double a, double b, double c, double d) + { + memset(p_vec, 0, sizeof(double)*N); + p_vec[0] = a; + p_vec[1] = b; + p_vec[2] = c; + p_vec[3] = d; + } + + Vector(const Vector &v) + { + for (int x = 0; x < N; x++) + p_vec[x] = v.p_vec[x]; + } + + ~Vector() + { + } + + uint8_t n() { return N; } + + double magnitude() const + { + double res = 0; + for (int i = 0; i < N; i++) + res += p_vec[i] * p_vec[i]; + + return sqrt(res); + } + + void normalize() + { + double mag = magnitude(); + if (isnan(mag) || mag == 0.0) + return; + + for (int i = 0; i < N; i++) + p_vec[i] /= mag; + } + + double dot(const Vector& v) const + { + double ret = 0; + for (int i = 0; i < N; i++) + ret += p_vec[i] * v.p_vec[i]; + + return ret; + } + + // The cross product is only valid for vectors with 3 dimensions, + // with the exception of higher dimensional stuff that is beyond + // the intended scope of this library. + // Only a definition for N==3 is given below this class, using + // cross() with another value for N will result in a link error. + Vector cross(const Vector& v) const; + + Vector scale(double scalar) const + { + Vector ret; + for(int i = 0; i < N; i++) + ret.p_vec[i] = p_vec[i] * scalar; + return ret; + } + + Vector invert() const + { + Vector ret; + for(int i = 0; i < N; i++) + ret.p_vec[i] = -p_vec[i]; + return ret; + } + + Vector& operator=(const Vector& v) + { + for (int x = 0; x < N; x++ ) + p_vec[x] = v.p_vec[x]; + return *this; + } + + double& operator [](int n) + { + return p_vec[n]; + } + + double operator [](int n) const + { + return p_vec[n]; + } + + double& operator ()(int n) + { + return p_vec[n]; + } + + double operator ()(int n) const + { + return p_vec[n]; + } + + Vector operator+(const Vector& v) const + { + Vector ret; + for(int i = 0; i < N; i++) + ret.p_vec[i] = p_vec[i] + v.p_vec[i]; + return ret; + } + + Vector operator-(const Vector& v) const + { + Vector ret; + for(int i = 0; i < N; i++) + ret.p_vec[i] = p_vec[i] - v.p_vec[i]; + return ret; + } + + Vector operator * (double scalar) const + { + return scale(scalar); + } + + Vector operator / (double scalar) const + { + Vector ret; + for(int i = 0; i < N; i++) + ret.p_vec[i] = p_vec[i] / scalar; + return ret; + } + + void toDegrees() + { + for(int i = 0; i < N; i++) + p_vec[i] *= 57.2957795131; //180/pi + } + + void toRadians() + { + for(int i = 0; i < N; i++) + p_vec[i] *= 0.01745329251; //pi/180 + } + + double& x() { return p_vec[0]; } + double& y() { return p_vec[1]; } + double& z() { return p_vec[2]; } + double x() const { return p_vec[0]; } + double y() const { return p_vec[1]; } + double z() const { return p_vec[2]; } + + +private: + double p_vec[N]; +}; + + +template <> +inline Vector<3> Vector<3>::cross(const Vector& v) const +{ + return Vector( + p_vec[1] * v.p_vec[2] - p_vec[2] * v.p_vec[1], + p_vec[2] * v.p_vec[0] - p_vec[0] * v.p_vec[2], + p_vec[0] * v.p_vec[1] - p_vec[1] * v.p_vec[0] + ); +} + +} // namespace + +#endif diff --git a/software/firmware/libraries/Adafruit_Sensor/Adafruit_Sensor.h b/software/firmware/libraries/Adafruit_Sensor/Adafruit_Sensor.h new file mode 100644 index 0000000..7742afc --- /dev/null +++ b/software/firmware/libraries/Adafruit_Sensor/Adafruit_Sensor.h @@ -0,0 +1,154 @@ +/* +* Copyright (C) 2008 The Android Open Source Project +* +* Licensed under the Apache License, Version 2.0 (the "License"); +* you may not use this file except in compliance with the License. +* You may obtain a copy of the License at +* +* http://www.apache.org/licenses/LICENSE-2.0 +* +* Unless required by applicable law or agreed to in writing, software< /span> +* distributed under the License is distributed on an "AS IS" BASIS, +* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +* See the License for the specific language governing permissions and +* limitations under the License. +*/ + +/* Update by K. Townsend (Adafruit Industries) for lighter typedefs, and + * extended sensor support to include color, voltage and current */ + +#ifndef _ADAFRUIT_SENSOR_H +#define _ADAFRUIT_SENSOR_H + +#if ARDUINO >= 100 + #include "Arduino.h" + #include "Print.h" +#else + #include "WProgram.h" +#endif + +/* Intentionally modeled after sensors.h in the Android API: + * https://github.com/android/platform_hardware_libhardware/blob/master/include/hardware/sensors.h */ + +/* Constants */ +#define SENSORS_GRAVITY_EARTH (9.80665F) /**< Earth's gravity in m/s^2 */ +#define SENSORS_GRAVITY_MOON (1.6F) /**< The moon's gravity in m/s^2 */ +#define SENSORS_GRAVITY_SUN (275.0F) /**< The sun's gravity in m/s^2 */ +#define SENSORS_GRAVITY_STANDARD (SENSORS_GRAVITY_EARTH) +#define SENSORS_MAGFIELD_EARTH_MAX (60.0F) /**< Maximum magnetic field on Earth's surface */ +#define SENSORS_MAGFIELD_EARTH_MIN (30.0F) /**< Minimum magnetic field on Earth's surface */ +#define SENSORS_PRESSURE_SEALEVELHPA (1013.25F) /**< Average sea level pressure is 1013.25 hPa */ +#define SENSORS_DPS_TO_RADS (0.017453293F) /**< Degrees/s to rad/s multiplier */ +#define SENSORS_GAUSS_TO_MICROTESLA (100) /**< Gauss to micro-Tesla multiplier */ + +/** Sensor types */ +typedef enum +{ + SENSOR_TYPE_ACCELEROMETER = (1), /**< Gravity + linear acceleration */ + SENSOR_TYPE_MAGNETIC_FIELD = (2), + SENSOR_TYPE_ORIENTATION = (3), + SENSOR_TYPE_GYROSCOPE = (4), + SENSOR_TYPE_LIGHT = (5), + SENSOR_TYPE_PRESSURE = (6), + SENSOR_TYPE_PROXIMITY = (8), + SENSOR_TYPE_GRAVITY = (9), + SENSOR_TYPE_LINEAR_ACCELERATION = (10), /**< Acceleration not including gravity */ + SENSOR_TYPE_ROTATION_VECTOR = (11), + SENSOR_TYPE_RELATIVE_HUMIDITY = (12), + SENSOR_TYPE_AMBIENT_TEMPERATURE = (13), + SENSOR_TYPE_VOLTAGE = (15), + SENSOR_TYPE_CURRENT = (16), + SENSOR_TYPE_COLOR = (17) +} sensors_type_t; + +/** struct sensors_vec_s is used to return a vector in a common format. */ +typedef struct { + union { + float v[3]; + struct { + float x; + float y; + float z; + }; + /* Orientation sensors */ + struct { + float roll; /**< Rotation around the longitudinal axis (the plane body, 'X axis'). Roll is positive and increasing when moving downward. -90°<=roll<=90° */ + float pitch; /**< Rotation around the lateral axis (the wing span, 'Y axis'). Pitch is positive and increasing when moving upwards. -180°<=pitch<=180°) */ + float heading; /**< Angle between the longitudinal axis (the plane body) and magnetic north, measured clockwise when viewing from the top of the device. 0-359° */ + }; + }; + int8_t status; + uint8_t reserved[3]; +} sensors_vec_t; + +/** struct sensors_color_s is used to return color data in a common format. */ +typedef struct { + union { + float c[3]; + /* RGB color space */ + struct { + float r; /**< Red component */ + float g; /**< Green component */ + float b; /**< Blue component */ + }; + }; + uint32_t rgba; /**< 24-bit RGBA value */ +} sensors_color_t; + +/* Sensor event (36 bytes) */ +/** struct sensor_event_s is used to provide a single sensor event in a common format. */ +typedef struct +{ + int32_t version; /**< must be sizeof(struct sensors_event_t) */ + int32_t sensor_id; /**< unique sensor identifier */ + int32_t type; /**< sensor type */ + int32_t reserved0; /**< reserved */ + int32_t timestamp; /**< time is in milliseconds */ + union + { + float data[4]; + sensors_vec_t acceleration; /**< acceleration values are in meter per second per second (m/s^2) */ + sensors_vec_t magnetic; /**< magnetic vector values are in micro-Tesla (uT) */ + sensors_vec_t orientation; /**< orientation values are in degrees */ + sensors_vec_t gyro; /**< gyroscope values are in rad/s */ + float temperature; /**< temperature is in degrees centigrade (Celsius) */ + float distance; /**< distance in centimeters */ + float light; /**< light in SI lux units */ + float pressure; /**< pressure in hectopascal (hPa) */ + float relative_humidity; /**< relative humidity in percent */ + float current; /**< current in milliamps (mA) */ + float voltage; /**< voltage in volts (V) */ + sensors_color_t color; /**< color in RGB component values */ + }; +} sensors_event_t; + +/* Sensor details (40 bytes) */ +/** struct sensor_s is used to describe basic information about a specific sensor. */ +typedef struct +{ + char name[12]; /**< sensor name */ + int32_t version; /**< version of the hardware + driver */ + int32_t sensor_id; /**< unique sensor identifier */ + int32_t type; /**< this sensor's type (ex. SENSOR_TYPE_LIGHT) */ + float max_value; /**< maximum value of this sensor's value in SI units */ + float min_value; /**< minimum value of this sensor's value in SI units */ + float resolution; /**< smallest difference between two values reported by this sensor */ + int32_t min_delay; /**< min delay in microseconds between events. zero = not a constant rate */ +} sensor_t; + +class Adafruit_Sensor { + public: + // Constructor(s) + Adafruit_Sensor() {} + virtual ~Adafruit_Sensor() {} + + // These must be defined by the subclass + virtual void enableAutoRange(bool enabled) {}; + virtual bool getEvent(sensors_event_t*) = 0; + virtual void getSensor(sensor_t*) = 0; + + private: + bool _autoRange; +}; + +#endif diff --git a/software/firmware/libraries/Adafruit_Sensor/README.md b/software/firmware/libraries/Adafruit_Sensor/README.md new file mode 100644 index 0000000..a4cd6ae --- /dev/null +++ b/software/firmware/libraries/Adafruit_Sensor/README.md @@ -0,0 +1,221 @@ +# Adafruit Unified Sensor Driver # + +Many small embedded systems exist to collect data from sensors, analyse the data, and either take an appropriate action or send that sensor data to another system for processing. + +One of the many challenges of embedded systems design is the fact that parts you used today may be out of production tomorrow, or system requirements may change and you may need to choose a different sensor down the road. + +Creating new drivers is a relatively easy task, but integrating them into existing systems is both error prone and time consuming since sensors rarely use the exact same units of measurement. + +By reducing all data to a single **sensors\_event\_t** 'type' and settling on specific, **standardised SI units** for each sensor family the same sensor types return values that are comparable with any other similar sensor. This enables you to switch sensor models with very little impact on the rest of the system, which can help mitigate some of the risks and problems of sensor availability and code reuse. + +The unified sensor abstraction layer is also useful for data-logging and data-transmission since you only have one well-known type to log or transmit over the air or wire. + +## Unified Sensor Drivers ## + +The following drivers are based on the Adafruit Unified Sensor Driver: + +**Accelerometers** + - [Adafruit\_ADXL345](https://github.com/adafruit/Adafruit_ADXL345) + - [Adafruit\_LSM303DLHC](https://github.com/adafruit/Adafruit_LSM303DLHC) + - [Adafruit\_MMA8451\_Library](https://github.com/adafruit/Adafruit_MMA8451_Library) + +**Gyroscope** + - [Adafruit\_L3GD20\_U](https://github.com/adafruit/Adafruit_L3GD20_U) + +**Light** + - [Adafruit\_TSL2561](https://github.com/adafruit/Adafruit_TSL2561) + - [Adafruit\_TSL2591\_Library](https://github.com/adafruit/Adafruit_TSL2591_Library) + +**Magnetometers** + - [Adafruit\_LSM303DLHC](https://github.com/adafruit/Adafruit_LSM303DLHC) + - [Adafruit\_HMC5883\_Unified](https://github.com/adafruit/Adafruit_HMC5883_Unified) + +**Barometric Pressure** + - [Adafruit\_BMP085\_Unified](https://github.com/adafruit/Adafruit_BMP085_Unified) + - [Adafruit\_BMP183\_Unified\_Library](https://github.com/adafruit/Adafruit_BMP183_Unified_Library) + +**Humidity & Temperature** + - [DHT-sensor-library](https://github.com/adafruit/DHT-sensor-library) + +**Orientation** + - [Adafruit_BNO055](https://github.com/adafruit/Adafruit_BNO055) + +## How Does it Work? ## + +Any driver that supports the Adafruit unified sensor abstraction layer will implement the Adafruit\_Sensor base class. There are two main typedefs and one enum defined in Adafruit_Sensor.h that are used to 'abstract' away the sensor details and values: + +**Sensor Types (sensors\_type\_t)** + +These pre-defined sensor types are used to properly handle the two related typedefs below, and allows us determine what types of units the sensor uses, etc. + +``` +/** Sensor types */ +typedef enum +{ + SENSOR_TYPE_ACCELEROMETER = (1), + SENSOR_TYPE_MAGNETIC_FIELD = (2), + SENSOR_TYPE_ORIENTATION = (3), + SENSOR_TYPE_GYROSCOPE = (4), + SENSOR_TYPE_LIGHT = (5), + SENSOR_TYPE_PRESSURE = (6), + SENSOR_TYPE_PROXIMITY = (8), + SENSOR_TYPE_GRAVITY = (9), + SENSOR_TYPE_LINEAR_ACCELERATION = (10), + SENSOR_TYPE_ROTATION_VECTOR = (11), + SENSOR_TYPE_RELATIVE_HUMIDITY = (12), + SENSOR_TYPE_AMBIENT_TEMPERATURE = (13), + SENSOR_TYPE_VOLTAGE = (15), + SENSOR_TYPE_CURRENT = (16), + SENSOR_TYPE_COLOR = (17) +} sensors_type_t; +``` + +**Sensor Details (sensor\_t)** + +This typedef describes the specific capabilities of this sensor, and allows us to know what sensor we are using beneath the abstraction layer. + +``` +/* Sensor details (40 bytes) */ +/** struct sensor_s is used to describe basic information about a specific sensor. */ +typedef struct +{ + char name[12]; + int32_t version; + int32_t sensor_id; + int32_t type; + float max_value; + float min_value; + float resolution; + int32_t min_delay; +} sensor_t; +``` + +The individual fields are intended to be used as follows: + +- **name**: The sensor name or ID, up to a maximum of twelve characters (ex. "MPL115A2") +- **version**: The version of the sensor HW and the driver to allow us to differentiate versions of the board or driver +- **sensor\_id**: A unique sensor identifier that is used to differentiate this specific sensor instance from any others that are present on the system or in the sensor network +- **type**: The sensor type, based on **sensors\_type\_t** in sensors.h +- **max\_value**: The maximum value that this sensor can return (in the appropriate SI unit) +- **min\_value**: The minimum value that this sensor can return (in the appropriate SI unit) +- **resolution**: The smallest difference between two values that this sensor can report (in the appropriate SI unit) +- **min\_delay**: The minimum delay in microseconds between two sensor events, or '0' if there is no constant sensor rate + +**Sensor Data/Events (sensors\_event\_t)** + +This typedef is used to return sensor data from any sensor supported by the abstraction layer, using standard SI units and scales. + +``` +/* Sensor event (36 bytes) */ +/** struct sensor_event_s is used to provide a single sensor event in a common format. */ +typedef struct +{ + int32_t version; + int32_t sensor_id; + int32_t type; + int32_t reserved0; + int32_t timestamp; + union + { + float data[4]; + sensors_vec_t acceleration; + sensors_vec_t magnetic; + sensors_vec_t orientation; + sensors_vec_t gyro; + float temperature; + float distance; + float light; + float pressure; + float relative_humidity; + float current; + float voltage; + sensors_color_t color; + }; +} sensors_event_t; +``` +It includes the following fields: + +- **version**: Contain 'sizeof(sensors\_event\_t)' to identify which version of the API we're using in case this changes in the future +- **sensor\_id**: A unique sensor identifier that is used to differentiate this specific sensor instance from any others that are present on the system or in the sensor network (must match the sensor\_id value in the corresponding sensor\_t enum above!) +- **type**: the sensor type, based on **sensors\_type\_t** in sensors.h +- **timestamp**: time in milliseconds when the sensor value was read +- **data[4]**: An array of four 32-bit values that allows us to encapsulate any type of sensor data via a simple union (further described below) + +**Required Functions** + +In addition to the two standard types and the sensor type enum, all drivers based on Adafruit_Sensor must also implement the following two functions: + +``` +bool getEvent(sensors_event_t*); +``` +Calling this function will populate the supplied sensors\_event\_t reference with the latest available sensor data. You should call this function as often as you want to update your data. + +``` +void getSensor(sensor_t*); +``` +Calling this function will provide some basic information about the sensor (the sensor name, driver version, min and max values, etc. + +**Standardised SI values for sensors\_event\_t** + +A key part of the abstraction layer is the standardisation of values on SI units of a particular scale, which is accomplished via the data[4] union in sensors\_event\_t above. This 16 byte union includes fields for each main sensor type, and uses the following SI units and scales: + +- **acceleration**: values are in **meter per second per second** (m/s^2) +- **magnetic**: values are in **micro-Tesla** (uT) +- **orientation**: values are in **degrees** +- **gyro**: values are in **rad/s** +- **temperature**: values in **degrees centigrade** (Celsius) +- **distance**: values are in **centimeters** +- **light**: values are in **SI lux** units +- **pressure**: values are in **hectopascal** (hPa) +- **relative\_humidity**: values are in **percent** +- **current**: values are in **milliamps** (mA) +- **voltage**: values are in **volts** (V) +- **color**: values are in 0..1.0 RGB channel luminosity and 32-bit RGBA format + +## The Unified Driver Abstraction Layer in Practice ## + +Using the unified sensor abstraction layer is relatively easy once a compliant driver has been created. + +Every compliant sensor can now be read using a single, well-known 'type' (sensors\_event\_t), and there is a standardised way of interrogating a sensor about its specific capabilities (via sensor\_t). + +An example of reading the [TSL2561](https://github.com/adafruit/Adafruit_TSL2561) light sensor can be seen below: + +``` + Adafruit_TSL2561 tsl = Adafruit_TSL2561(TSL2561_ADDR_FLOAT, 12345); + ... + /* Get a new sensor event */ + sensors_event_t event; + tsl.getEvent(&event); + + /* Display the results (light is measured in lux) */ + if (event.light) + { + Serial.print(event.light); Serial.println(" lux"); + } + else + { + /* If event.light = 0 lux the sensor is probably saturated + and no reliable data could be generated! */ + Serial.println("Sensor overload"); + } +``` + +Similarly, we can get the basic technical capabilities of this sensor with the following code: + +``` + sensor_t sensor; + + sensor_t sensor; + tsl.getSensor(&sensor); + + /* Display the sensor details */ + Serial.println("------------------------------------"); + Serial.print ("Sensor: "); Serial.println(sensor.name); + Serial.print ("Driver Ver: "); Serial.println(sensor.version); + Serial.print ("Unique ID: "); Serial.println(sensor.sensor_id); + Serial.print ("Max Value: "); Serial.print(sensor.max_value); Serial.println(" lux"); + Serial.print ("Min Value: "); Serial.print(sensor.min_value); Serial.println(" lux"); + Serial.print ("Resolution: "); Serial.print(sensor.resolution); Serial.println(" lux"); + Serial.println("------------------------------------"); + Serial.println(""); +``` diff --git a/software/firmware/libraries/Adafruit_Sensor/library.properties b/software/firmware/libraries/Adafruit_Sensor/library.properties new file mode 100644 index 0000000..fa7eefa --- /dev/null +++ b/software/firmware/libraries/Adafruit_Sensor/library.properties @@ -0,0 +1,9 @@ +name=Adafruit Unified Sensor +version=1.0.2 +author=Adafruit +maintainer=Adafruit +sentence=Required for all Adafruit Unified Sensor based libraries. +paragraph=A unified sensor abstraction layer used by many Adafruit sensor libraries. +category=Sensors +url=https://github.com/adafruit/Adafruit_Sensor +architectures=* diff --git a/software/firmware/libraries/NeoGPS/.gitattributes b/software/firmware/libraries/NeoGPS/.gitattributes new file mode 100644 index 0000000..bdb0cab --- /dev/null +++ b/software/firmware/libraries/NeoGPS/.gitattributes @@ -0,0 +1,17 @@ +# Auto detect text files and perform LF normalization +* text=auto + +# Custom for Visual Studio +*.cs diff=csharp + +# Standard to msysgit +*.doc diff=astextplain +*.DOC diff=astextplain +*.docx diff=astextplain +*.DOCX diff=astextplain +*.dot diff=astextplain +*.DOT diff=astextplain +*.pdf diff=astextplain +*.PDF diff=astextplain +*.rtf diff=astextplain +*.RTF diff=astextplain diff --git a/software/firmware/libraries/NeoGPS/.gitignore b/software/firmware/libraries/NeoGPS/.gitignore new file mode 100644 index 0000000..96374c4 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/.gitignore @@ -0,0 +1,43 @@ +# Windows image file caches +Thumbs.db +ehthumbs.db + +# Folder config file +Desktop.ini + +# Recycle Bin used on file shares +$RECYCLE.BIN/ + +# Windows Installer files +*.cab +*.msi +*.msm +*.msp + +# Windows shortcuts +*.lnk + +# ========================= +# Operating System Files +# ========================= + +# OSX +# ========================= + +.DS_Store +.AppleDouble +.LSOverride + +# Thumbnails +._* + +# Files that might appear on external disk +.Spotlight-V100 +.Trashes + +# Directories potentially created on remote AFP share +.AppleDB +.AppleDesktop +Network Trash Folder +Temporary Items +.apdisk diff --git a/software/firmware/libraries/NeoGPS/LICENSE b/software/firmware/libraries/NeoGPS/LICENSE new file mode 100644 index 0000000..9cecc1d --- /dev/null +++ b/software/firmware/libraries/NeoGPS/LICENSE @@ -0,0 +1,674 @@ + GNU GENERAL PUBLIC LICENSE + Version 3, 29 June 2007 + + Copyright (C) 2007 Free Software Foundation, Inc. + Everyone is permitted to copy and distribute verbatim copies + of this license document, but changing it is not allowed. + + Preamble + + The GNU General Public License is a free, copyleft license for +software and other kinds of works. + + The licenses for most software and other practical works are designed +to take away your freedom to share and change the works. By contrast, +the GNU General Public License is intended to guarantee your freedom to +share and change all versions of a program--to make sure it remains free +software for all its users. We, the Free Software Foundation, use the +GNU General Public License for most of our software; it applies also to +any other work released this way by its authors. You can apply it to +your programs, too. + + When we speak of free software, we are referring to freedom, not +price. Our General Public Licenses are designed to make sure that you +have the freedom to distribute copies of free software (and charge for +them if you wish), that you receive source code or can get it if you +want it, that you can change the software or use pieces of it in new +free programs, and that you know you can do these things. + + To protect your rights, we need to prevent others from denying you +these rights or asking you to surrender the rights. Therefore, you have +certain responsibilities if you distribute copies of the software, or if +you modify it: responsibilities to respect the freedom of others. + + For example, if you distribute copies of such a program, whether +gratis or for a fee, you must pass on to the recipients the same +freedoms that you received. You must make sure that they, too, receive +or can get the source code. And you must show them these terms so they +know their rights. + + Developers that use the GNU GPL protect your rights with two steps: +(1) assert copyright on the software, and (2) offer you this License +giving you legal permission to copy, distribute and/or modify it. + + For the developers' and authors' protection, the GPL clearly explains +that there is no warranty for this free software. For both users' and +authors' sake, the GPL requires that modified versions be marked as +changed, so that their problems will not be attributed erroneously to +authors of previous versions. + + Some devices are designed to deny users access to install or run +modified versions of the software inside them, although the manufacturer +can do so. This is fundamentally incompatible with the aim of +protecting users' freedom to change the software. The systematic +pattern of such abuse occurs in the area of products for individuals to +use, which is precisely where it is most unacceptable. Therefore, we +have designed this version of the GPL to prohibit the practice for those +products. If such problems arise substantially in other domains, we +stand ready to extend this provision to those domains in future versions +of the GPL, as needed to protect the freedom of users. + + Finally, every program is threatened constantly by software patents. +States should not allow patents to restrict development and use of +software on general-purpose computers, but in those that do, we wish to +avoid the special danger that patents applied to a free program could +make it effectively proprietary. To prevent this, the GPL assures that +patents cannot be used to render the program non-free. + + The precise terms and conditions for copying, distribution and +modification follow. + + TERMS AND CONDITIONS + + 0. Definitions. + + "This License" refers to version 3 of the GNU General Public License. + + "Copyright" also means copyright-like laws that apply to other kinds of +works, such as semiconductor masks. + + "The Program" refers to any copyrightable work licensed under this +License. Each licensee is addressed as "you". "Licensees" and +"recipients" may be individuals or organizations. + + To "modify" a work means to copy from or adapt all or part of the work +in a fashion requiring copyright permission, other than the making of an +exact copy. The resulting work is called a "modified version" of the +earlier work or a work "based on" the earlier work. + + A "covered work" means either the unmodified Program or a work based +on the Program. + + To "propagate" a work means to do anything with it that, without +permission, would make you directly or secondarily liable for +infringement under applicable copyright law, except executing it on a +computer or modifying a private copy. Propagation includes copying, +distribution (with or without modification), making available to the +public, and in some countries other activities as well. + + To "convey" a work means any kind of propagation that enables other +parties to make or receive copies. Mere interaction with a user through +a computer network, with no transfer of a copy, is not conveying. + + An interactive user interface displays "Appropriate Legal Notices" +to the extent that it includes a convenient and prominently visible +feature that (1) displays an appropriate copyright notice, and (2) +tells the user that there is no warranty for the work (except to the +extent that warranties are provided), that licensees may convey the +work under this License, and how to view a copy of this License. If +the interface presents a list of user commands or options, such as a +menu, a prominent item in the list meets this criterion. + + 1. Source Code. + + The "source code" for a work means the preferred form of the work +for making modifications to it. "Object code" means any non-source +form of a work. + + A "Standard Interface" means an interface that either is an official +standard defined by a recognized standards body, or, in the case of +interfaces specified for a particular programming language, one that +is widely used among developers working in that language. + + The "System Libraries" of an executable work include anything, other +than the work as a whole, that (a) is included in the normal form of +packaging a Major Component, but which is not part of that Major +Component, and (b) serves only to enable use of the work with that +Major Component, or to implement a Standard Interface for which an +implementation is available to the public in source code form. A +"Major Component", in this context, means a major essential component +(kernel, window system, and so on) of the specific operating system +(if any) on which the executable work runs, or a compiler used to +produce the work, or an object code interpreter used to run it. + + The "Corresponding Source" for a work in object code form means all +the source code needed to generate, install, and (for an executable +work) run the object code and to modify the work, including scripts to +control those activities. However, it does not include the work's +System Libraries, or general-purpose tools or generally available free +programs which are used unmodified in performing those activities but +which are not part of the work. For example, Corresponding Source +includes interface definition files associated with source files for +the work, and the source code for shared libraries and dynamically +linked subprograms that the work is specifically designed to require, +such as by intimate data communication or control flow between those +subprograms and other parts of the work. + + The Corresponding Source need not include anything that users +can regenerate automatically from other parts of the Corresponding +Source. + + The Corresponding Source for a work in source code form is that +same work. + + 2. Basic Permissions. + + All rights granted under this License are granted for the term of +copyright on the Program, and are irrevocable provided the stated +conditions are met. This License explicitly affirms your unlimited +permission to run the unmodified Program. The output from running a +covered work is covered by this License only if the output, given its +content, constitutes a covered work. This License acknowledges your +rights of fair use or other equivalent, as provided by copyright law. + + You may make, run and propagate covered works that you do not +convey, without conditions so long as your license otherwise remains +in force. You may convey covered works to others for the sole purpose +of having them make modifications exclusively for you, or provide you +with facilities for running those works, provided that you comply with +the terms of this License in conveying all material for which you do +not control copyright. Those thus making or running the covered works +for you must do so exclusively on your behalf, under your direction +and control, on terms that prohibit them from making any copies of +your copyrighted material outside their relationship with you. + + Conveying under any other circumstances is permitted solely under +the conditions stated below. Sublicensing is not allowed; section 10 +makes it unnecessary. + + 3. Protecting Users' Legal Rights From Anti-Circumvention Law. + + No covered work shall be deemed part of an effective technological +measure under any applicable law fulfilling obligations under article +11 of the WIPO copyright treaty adopted on 20 December 1996, or +similar laws prohibiting or restricting circumvention of such +measures. + + When you convey a covered work, you waive any legal power to forbid +circumvention of technological measures to the extent such circumvention +is effected by exercising rights under this License with respect to +the covered work, and you disclaim any intention to limit operation or +modification of the work as a means of enforcing, against the work's +users, your or third parties' legal rights to forbid circumvention of +technological measures. + + 4. Conveying Verbatim Copies. + + You may convey verbatim copies of the Program's source code as you +receive it, in any medium, provided that you conspicuously and +appropriately publish on each copy an appropriate copyright notice; +keep intact all notices stating that this License and any +non-permissive terms added in accord with section 7 apply to the code; +keep intact all notices of the absence of any warranty; and give all +recipients a copy of this License along with the Program. + + You may charge any price or no price for each copy that you convey, +and you may offer support or warranty protection for a fee. + + 5. Conveying Modified Source Versions. + + You may convey a work based on the Program, or the modifications to +produce it from the Program, in the form of source code under the +terms of section 4, provided that you also meet all of these conditions: + + a) The work must carry prominent notices stating that you modified + it, and giving a relevant date. + + b) The work must carry prominent notices stating that it is + released under this License and any conditions added under section + 7. This requirement modifies the requirement in section 4 to + "keep intact all notices". + + c) You must license the entire work, as a whole, under this + License to anyone who comes into possession of a copy. This + License will therefore apply, along with any applicable section 7 + additional terms, to the whole of the work, and all its parts, + regardless of how they are packaged. This License gives no + permission to license the work in any other way, but it does not + invalidate such permission if you have separately received it. + + d) If the work has interactive user interfaces, each must display + Appropriate Legal Notices; however, if the Program has interactive + interfaces that do not display Appropriate Legal Notices, your + work need not make them do so. + + A compilation of a covered work with other separate and independent +works, which are not by their nature extensions of the covered work, +and which are not combined with it such as to form a larger program, +in or on a volume of a storage or distribution medium, is called an +"aggregate" if the compilation and its resulting copyright are not +used to limit the access or legal rights of the compilation's users +beyond what the individual works permit. Inclusion of a covered work +in an aggregate does not cause this License to apply to the other +parts of the aggregate. + + 6. Conveying Non-Source Forms. + + You may convey a covered work in object code form under the terms +of sections 4 and 5, provided that you also convey the +machine-readable Corresponding Source under the terms of this License, +in one of these ways: + + a) Convey the object code in, or embodied in, a physical product + (including a physical distribution medium), accompanied by the + Corresponding Source fixed on a durable physical medium + customarily used for software interchange. + + b) Convey the object code in, or embodied in, a physical product + (including a physical distribution medium), accompanied by a + written offer, valid for at least three years and valid for as + long as you offer spare parts or customer support for that product + model, to give anyone who possesses the object code either (1) a + copy of the Corresponding Source for all the software in the + product that is covered by this License, on a durable physical + medium customarily used for software interchange, for a price no + more than your reasonable cost of physically performing this + conveying of source, or (2) access to copy the + Corresponding Source from a network server at no charge. + + c) Convey individual copies of the object code with a copy of the + written offer to provide the Corresponding Source. This + alternative is allowed only occasionally and noncommercially, and + only if you received the object code with such an offer, in accord + with subsection 6b. + + d) Convey the object code by offering access from a designated + place (gratis or for a charge), and offer equivalent access to the + Corresponding Source in the same way through the same place at no + further charge. You need not require recipients to copy the + Corresponding Source along with the object code. If the place to + copy the object code is a network server, the Corresponding Source + may be on a different server (operated by you or a third party) + that supports equivalent copying facilities, provided you maintain + clear directions next to the object code saying where to find the + Corresponding Source. Regardless of what server hosts the + Corresponding Source, you remain obligated to ensure that it is + available for as long as needed to satisfy these requirements. + + e) Convey the object code using peer-to-peer transmission, provided + you inform other peers where the object code and Corresponding + Source of the work are being offered to the general public at no + charge under subsection 6d. + + A separable portion of the object code, whose source code is excluded +from the Corresponding Source as a System Library, need not be +included in conveying the object code work. + + A "User Product" is either (1) a "consumer product", which means any +tangible personal property which is normally used for personal, family, +or household purposes, or (2) anything designed or sold for incorporation +into a dwelling. In determining whether a product is a consumer product, +doubtful cases shall be resolved in favor of coverage. For a particular +product received by a particular user, "normally used" refers to a +typical or common use of that class of product, regardless of the status +of the particular user or of the way in which the particular user +actually uses, or expects or is expected to use, the product. A product +is a consumer product regardless of whether the product has substantial +commercial, industrial or non-consumer uses, unless such uses represent +the only significant mode of use of the product. + + "Installation Information" for a User Product means any methods, +procedures, authorization keys, or other information required to install +and execute modified versions of a covered work in that User Product from +a modified version of its Corresponding Source. The information must +suffice to ensure that the continued functioning of the modified object +code is in no case prevented or interfered with solely because +modification has been made. + + If you convey an object code work under this section in, or with, or +specifically for use in, a User Product, and the conveying occurs as +part of a transaction in which the right of possession and use of the +User Product is transferred to the recipient in perpetuity or for a +fixed term (regardless of how the transaction is characterized), the +Corresponding Source conveyed under this section must be accompanied +by the Installation Information. But this requirement does not apply +if neither you nor any third party retains the ability to install +modified object code on the User Product (for example, the work has +been installed in ROM). + + The requirement to provide Installation Information does not include a +requirement to continue to provide support service, warranty, or updates +for a work that has been modified or installed by the recipient, or for +the User Product in which it has been modified or installed. Access to a +network may be denied when the modification itself materially and +adversely affects the operation of the network or violates the rules and +protocols for communication across the network. + + Corresponding Source conveyed, and Installation Information provided, +in accord with this section must be in a format that is publicly +documented (and with an implementation available to the public in +source code form), and must require no special password or key for +unpacking, reading or copying. + + 7. Additional Terms. + + "Additional permissions" are terms that supplement the terms of this +License by making exceptions from one or more of its conditions. +Additional permissions that are applicable to the entire Program shall +be treated as though they were included in this License, to the extent +that they are valid under applicable law. If additional permissions +apply only to part of the Program, that part may be used separately +under those permissions, but the entire Program remains governed by +this License without regard to the additional permissions. + + When you convey a copy of a covered work, you may at your option +remove any additional permissions from that copy, or from any part of +it. (Additional permissions may be written to require their own +removal in certain cases when you modify the work.) You may place +additional permissions on material, added by you to a covered work, +for which you have or can give appropriate copyright permission. + + Notwithstanding any other provision of this License, for material you +add to a covered work, you may (if authorized by the copyright holders of +that material) supplement the terms of this License with terms: + + a) Disclaiming warranty or limiting liability differently from the + terms of sections 15 and 16 of this License; or + + b) Requiring preservation of specified reasonable legal notices or + author attributions in that material or in the Appropriate Legal + Notices displayed by works containing it; or + + c) Prohibiting misrepresentation of the origin of that material, or + requiring that modified versions of such material be marked in + reasonable ways as different from the original version; or + + d) Limiting the use for publicity purposes of names of licensors or + authors of the material; or + + e) Declining to grant rights under trademark law for use of some + trade names, trademarks, or service marks; or + + f) Requiring indemnification of licensors and authors of that + material by anyone who conveys the material (or modified versions of + it) with contractual assumptions of liability to the recipient, for + any liability that these contractual assumptions directly impose on + those licensors and authors. + + All other non-permissive additional terms are considered "further +restrictions" within the meaning of section 10. If the Program as you +received it, or any part of it, contains a notice stating that it is +governed by this License along with a term that is a further +restriction, you may remove that term. If a license document contains +a further restriction but permits relicensing or conveying under this +License, you may add to a covered work material governed by the terms +of that license document, provided that the further restriction does +not survive such relicensing or conveying. + + If you add terms to a covered work in accord with this section, you +must place, in the relevant source files, a statement of the +additional terms that apply to those files, or a notice indicating +where to find the applicable terms. + + Additional terms, permissive or non-permissive, may be stated in the +form of a separately written license, or stated as exceptions; +the above requirements apply either way. + + 8. Termination. + + You may not propagate or modify a covered work except as expressly +provided under this License. Any attempt otherwise to propagate or +modify it is void, and will automatically terminate your rights under +this License (including any patent licenses granted under the third +paragraph of section 11). + + However, if you cease all violation of this License, then your +license from a particular copyright holder is reinstated (a) +provisionally, unless and until the copyright holder explicitly and +finally terminates your license, and (b) permanently, if the copyright +holder fails to notify you of the violation by some reasonable means +prior to 60 days after the cessation. + + Moreover, your license from a particular copyright holder is +reinstated permanently if the copyright holder notifies you of the +violation by some reasonable means, this is the first time you have +received notice of violation of this License (for any work) from that +copyright holder, and you cure the violation prior to 30 days after +your receipt of the notice. + + Termination of your rights under this section does not terminate the +licenses of parties who have received copies or rights from you under +this License. If your rights have been terminated and not permanently +reinstated, you do not qualify to receive new licenses for the same +material under section 10. + + 9. Acceptance Not Required for Having Copies. + + You are not required to accept this License in order to receive or +run a copy of the Program. Ancillary propagation of a covered work +occurring solely as a consequence of using peer-to-peer transmission +to receive a copy likewise does not require acceptance. However, +nothing other than this License grants you permission to propagate or +modify any covered work. These actions infringe copyright if you do +not accept this License. Therefore, by modifying or propagating a +covered work, you indicate your acceptance of this License to do so. + + 10. Automatic Licensing of Downstream Recipients. + + Each time you convey a covered work, the recipient automatically +receives a license from the original licensors, to run, modify and +propagate that work, subject to this License. You are not responsible +for enforcing compliance by third parties with this License. + + An "entity transaction" is a transaction transferring control of an +organization, or substantially all assets of one, or subdividing an +organization, or merging organizations. If propagation of a covered +work results from an entity transaction, each party to that +transaction who receives a copy of the work also receives whatever +licenses to the work the party's predecessor in interest had or could +give under the previous paragraph, plus a right to possession of the +Corresponding Source of the work from the predecessor in interest, if +the predecessor has it or can get it with reasonable efforts. + + You may not impose any further restrictions on the exercise of the +rights granted or affirmed under this License. For example, you may +not impose a license fee, royalty, or other charge for exercise of +rights granted under this License, and you may not initiate litigation +(including a cross-claim or counterclaim in a lawsuit) alleging that +any patent claim is infringed by making, using, selling, offering for +sale, or importing the Program or any portion of it. + + 11. Patents. + + A "contributor" is a copyright holder who authorizes use under this +License of the Program or a work on which the Program is based. The +work thus licensed is called the contributor's "contributor version". + + A contributor's "essential patent claims" are all patent claims +owned or controlled by the contributor, whether already acquired or +hereafter acquired, that would be infringed by some manner, permitted +by this License, of making, using, or selling its contributor version, +but do not include claims that would be infringed only as a +consequence of further modification of the contributor version. For +purposes of this definition, "control" includes the right to grant +patent sublicenses in a manner consistent with the requirements of +this License. + + Each contributor grants you a non-exclusive, worldwide, royalty-free +patent license under the contributor's essential patent claims, to +make, use, sell, offer for sale, import and otherwise run, modify and +propagate the contents of its contributor version. + + In the following three paragraphs, a "patent license" is any express +agreement or commitment, however denominated, not to enforce a patent +(such as an express permission to practice a patent or covenant not to +sue for patent infringement). To "grant" such a patent license to a +party means to make such an agreement or commitment not to enforce a +patent against the party. + + If you convey a covered work, knowingly relying on a patent license, +and the Corresponding Source of the work is not available for anyone +to copy, free of charge and under the terms of this License, through a +publicly available network server or other readily accessible means, +then you must either (1) cause the Corresponding Source to be so +available, or (2) arrange to deprive yourself of the benefit of the +patent license for this particular work, or (3) arrange, in a manner +consistent with the requirements of this License, to extend the patent +license to downstream recipients. "Knowingly relying" means you have +actual knowledge that, but for the patent license, your conveying the +covered work in a country, or your recipient's use of the covered work +in a country, would infringe one or more identifiable patents in that +country that you have reason to believe are valid. + + If, pursuant to or in connection with a single transaction or +arrangement, you convey, or propagate by procuring conveyance of, a +covered work, and grant a patent license to some of the parties +receiving the covered work authorizing them to use, propagate, modify +or convey a specific copy of the covered work, then the patent license +you grant is automatically extended to all recipients of the covered +work and works based on it. + + A patent license is "discriminatory" if it does not include within +the scope of its coverage, prohibits the exercise of, or is +conditioned on the non-exercise of one or more of the rights that are +specifically granted under this License. You may not convey a covered +work if you are a party to an arrangement with a third party that is +in the business of distributing software, under which you make payment +to the third party based on the extent of your activity of conveying +the work, and under which the third party grants, to any of the +parties who would receive the covered work from you, a discriminatory +patent license (a) in connection with copies of the covered work +conveyed by you (or copies made from those copies), or (b) primarily +for and in connection with specific products or compilations that +contain the covered work, unless you entered into that arrangement, +or that patent license was granted, prior to 28 March 2007. + + Nothing in this License shall be construed as excluding or limiting +any implied license or other defenses to infringement that may +otherwise be available to you under applicable patent law. + + 12. No Surrender of Others' Freedom. + + If conditions are imposed on you (whether by court order, agreement or +otherwise) that contradict the conditions of this License, they do not +excuse you from the conditions of this License. If you cannot convey a +covered work so as to satisfy simultaneously your obligations under this +License and any other pertinent obligations, then as a consequence you may +not convey it at all. For example, if you agree to terms that obligate you +to collect a royalty for further conveying from those to whom you convey +the Program, the only way you could satisfy both those terms and this +License would be to refrain entirely from conveying the Program. + + 13. Use with the GNU Affero General Public License. + + Notwithstanding any other provision of this License, you have +permission to link or combine any covered work with a work licensed +under version 3 of the GNU Affero General Public License into a single +combined work, and to convey the resulting work. The terms of this +License will continue to apply to the part which is the covered work, +but the special requirements of the GNU Affero General Public License, +section 13, concerning interaction through a network will apply to the +combination as such. + + 14. Revised Versions of this License. + + The Free Software Foundation may publish revised and/or new versions of +the GNU General Public License from time to time. Such new versions will +be similar in spirit to the present version, but may differ in detail to +address new problems or concerns. + + Each version is given a distinguishing version number. If the +Program specifies that a certain numbered version of the GNU General +Public License "or any later version" applies to it, you have the +option of following the terms and conditions either of that numbered +version or of any later version published by the Free Software +Foundation. If the Program does not specify a version number of the +GNU General Public License, you may choose any version ever published +by the Free Software Foundation. + + If the Program specifies that a proxy can decide which future +versions of the GNU General Public License can be used, that proxy's +public statement of acceptance of a version permanently authorizes you +to choose that version for the Program. + + Later license versions may give you additional or different +permissions. However, no additional obligations are imposed on any +author or copyright holder as a result of your choosing to follow a +later version. + + 15. Disclaimer of Warranty. + + THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY +APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT +HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY +OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, +THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR +PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM +IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF +ALL NECESSARY SERVICING, REPAIR OR CORRECTION. + + 16. Limitation of Liability. + + IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING +WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS +THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY +GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE +USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF +DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD +PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS), +EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF +SUCH DAMAGES. + + 17. Interpretation of Sections 15 and 16. + + If the disclaimer of warranty and limitation of liability provided +above cannot be given local legal effect according to their terms, +reviewing courts shall apply local law that most closely approximates +an absolute waiver of all civil liability in connection with the +Program, unless a warranty or assumption of liability accompanies a +copy of the Program in return for a fee. + + END OF TERMS AND CONDITIONS + + How to Apply These Terms to Your New Programs + + If you develop a new program, and you want it to be of the greatest +possible use to the public, the best way to achieve this is to make it +free software which everyone can redistribute and change under these terms. + + To do so, attach the following notices to the program. It is safest +to attach them to the start of each source file to most effectively +state the exclusion of warranty; and each file should have at least +the "copyright" line and a pointer to where the full notice is found. + + {one line to give the program's name and a brief idea of what it does.} + Copyright (C) {year} {name of author} + + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + +Also add information on how to contact you by electronic and paper mail. + + If the program does terminal interaction, make it output a short +notice like this when it starts in an interactive mode: + + {project} Copyright (C) {year} {fullname} + This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'. + This is free software, and you are welcome to redistribute it + under certain conditions; type `show c' for details. + +The hypothetical commands `show w' and `show c' should show the appropriate +parts of the General Public License. Of course, your program's commands +might be different; for a GUI interface, you would use an "about box". + + You should also get your employer (if you work as a programmer) or school, +if any, to sign a "copyright disclaimer" for the program, if necessary. +For more information on this, and how to apply and follow the GNU GPL, see +. + + The GNU General Public License does not permit incorporating your program +into proprietary programs. If your program is a subroutine library, you +may consider it more useful to permit linking proprietary applications with +the library. If this is what you want to do, use the GNU Lesser General +Public License instead of this License. But first, please read +. diff --git a/software/firmware/libraries/NeoGPS/README.md b/software/firmware/libraries/NeoGPS/README.md new file mode 100644 index 0000000..cf24c80 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/README.md @@ -0,0 +1,79 @@ +NeoGPS +====== + +This fully-configurable Arduino library uses _**minimal**_ RAM, PROGMEM and CPU time, +requiring as few as _**10 bytes of RAM**_, **866 bytes of PROGMEM**, and **less than 1mS of CPU time** per sentence. + +It supports the following protocols and messages: + +#### NMEA 0183 +* GPGGA - System fix data +* GPGLL - Geographic Latitude and Longitude +* GPGSA - DOP and active satellites +* GPGST - Pseudo Range Error Statistics +* GPGSV - Satellites in View +* GPRMC - Recommended Minimum specific GPS/Transit data +* GPVTG - Course over ground and Ground speed +* GPZDA - UTC Time and Date + +The "GP" prefix usually indicates an original [GPS](https://en.wikipedia.org/wiki/Satellite_navigation#GPS) source. NeoGPS parses *all* Talker IDs, including + * "GL" ([GLONASS](https://en.wikipedia.org/wiki/Satellite_navigation#GLONASS)), + * "BD" or "GB" ([BeiDou](https://en.wikipedia.org/wiki/Satellite_navigation#BeiDou)), + * "GA" ([Galileo](https://en.wikipedia.org/wiki/Satellite_navigation#Galileo)), and + * "GN" (mixed) + +This means that GLRMC, GBRMC or BDRMC, GARMC and GNRMC from the latest GPS devices (e.g., ublox M8N) will also be correctly parsed. See discussion of Talker IDs in [Configurations](extras/doc/Configurations.md#enabledisable-the-talker-id-and-manufacturer-id-processing). + +Most applications can be fully implemented with the standard NMEA messages above. They are supported by almost all GPS manufacturers. Additional messages can be added through derived classes. + +Most applications will use this simple, familiar loop structure: +``` +NMEAGPS gps; +gps_fix fix; + +void loop() +{ + while (gps.available( gps_port )) { + fix = gps.read(); + doSomeWork( fix ); + } +} +``` +For more information on this loop, see the [Usage](extras/doc/Data%20Model.md#usage) section on the [Data Model](extras/doc/Data%20Model.md) page. + +(This is the plain Arduino version of the [CosaGPS](https://github.com/SlashDevin/CosaGPS) library for [Cosa](https://github.com/mikaelpatel/Cosa).) + +Goals +====== +In an attempt to be reusable in a variety of different programming styles, this library supports: +* resource-constrained environments (e.g., ATTINY targets) +* sync or async operation (reading in `loop()` vs interrupt processing) +* event or polling (deferred handling vs. continuous calls in `loop()`) +* coherent fixes (merged from multiple sentences) vs. individual sentences +* optional buffering of fixes +* optional floating point +* configurable message sets, including hooks for implementing proprietary NMEA messages +* configurable message fields +* multiple protocols from same device +* any kind of input stream (Serial, [NeoSWSerial](https://github.com/SlashDevin/NeoSWSerial), I2C, PROGMEM arrays, etc.) + +Inconceivable! +============= + +Don't believe it? Check out these detailed sections: + +Section | Description +-------- | ------------ +[License](LICENSE) | The Fine Print +[Installing](extras/doc/Installing.md) | Copying files +[Data Model](extras/doc/Data%20Model.md) | How to parse and use GPS data +[Configurations](extras/doc/Configurations.md) | Tailoring NeoGPS to your needs +[Performance](extras/doc/Performance.md) | 37% to 72% faster! Really! +[RAM requirements](extras/doc/RAM.md) | Doing it without buffers! +[Program Space requirements](extras/doc/Program.md) | Making it fit +[Examples](extras/doc/Examples.md) | Programming styles +[Troubleshooting](extras/doc/Troubleshooting.md) | Troubleshooting +[Extending NeoGPS](extras/doc/Extending.md) | Using specific devices +[ublox](extras/doc/ublox.md) | ublox-specific code +[Tradeoffs](extras/doc/Tradeoffs.md) | Comparing to other libraries +[Acknowledgements](extras/doc/Acknowledgements.md) | Thanks! diff --git a/software/firmware/libraries/NeoGPS/examples/NMEA/NMEA.ino b/software/firmware/libraries/NeoGPS/examples/NMEA/NMEA.ino new file mode 100644 index 0000000..de10903 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/examples/NMEA/NMEA.ino @@ -0,0 +1,168 @@ +#include + +//====================================================================== +// Program: NMEA.ino +// +// Description: This program uses the fix-oriented methods available() and +// read() to handle complete fix structures. +// +// When the last character of the LAST_SENTENCE_IN_INTERVAL (see NMEAGPS_cfg.h) +// is decoded, a completed fix structure becomes available and is returned +// from read(). The new fix is saved the 'fix' structure, and can be used +// anywhere, at any time. +// +// If no messages are enabled in NMEAGPS_cfg.h, or +// no 'gps_fix' members are enabled in GPSfix_cfg.h, no information will be +// parsed, copied or printed. +// +// Prerequisites: +// 1) Your GPS device has been correctly powered. +// Be careful when connecting 3.3V devices. +// 2) Your GPS device is correctly connected to an Arduino serial port. +// See GPSport.h for the default connections. +// 3) You know the default baud rate of your GPS device. +// If 9600 does not work, use NMEAdiagnostic.ino to +// scan for the correct baud rate. +// 4) LAST_SENTENCE_IN_INTERVAL is defined to be the sentence that is +// sent *last* in each update interval (usually once per second). +// The default is NMEAGPS::NMEA_RMC (see NMEAGPS_cfg.h). Other +// programs may need to use the sentence identified by NMEAorder.ino. +// 5) NMEAGPS_RECOGNIZE_ALL is defined in NMEAGPS_cfg.h +// +// 'Serial' is for debug output to the Serial Monitor window. +// +// License: +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . +// +//====================================================================== + +//------------------------------------------------------------------------- +// The GPSport.h include file tries to choose a default serial port +// for the GPS device. If you know which serial port you want to use, +// edit the GPSport.h file. + +#include + +//------------------------------------------------------------ +// For the NeoGPS example programs, "Streamers" is common set +// of printing and formatting routines for GPS data, in a +// Comma-Separated Values text format (aka CSV). The CSV +// data will be printed to the "debug output device". +// If you don't need these formatters, simply delete this section. + +#include + +//------------------------------------------------------------ +// This object parses received characters +// into the gps.fix() data structure + +static NMEAGPS gps; + +//------------------------------------------------------------ +// Define a set of GPS fix information. It will +// hold on to the various pieces as they are received from +// an RMC sentence. It can be used anywhere in your sketch. + +static gps_fix fix; + +//---------------------------------------------------------------- +// This function gets called about once per second, during the GPS +// quiet time. It's the best place to do anything that might take +// a while: print a bunch of things, write to SD, send an SMS, etc. +// +// By doing the "hard" work during the quiet time, the CPU can get back to +// reading the GPS chars as they come in, so that no chars are lost. + +static void doSomeWork() +{ + // Print all the things! + + trace_all( DEBUG_PORT, gps, fix ); + +} // doSomeWork + +//------------------------------------ +// This is the main GPS parsing loop. + +static void GPSloop() +{ + while (gps.available( gpsPort )) { + fix = gps.read(); + doSomeWork(); + } + +} // GPSloop + +//-------------------------- + +void setup() +{ + DEBUG_PORT.begin(9600); + while (!DEBUG_PORT) + ; + + DEBUG_PORT.print( F("NMEA.INO: started\n") ); + DEBUG_PORT.print( F(" fix object size = ") ); + DEBUG_PORT.println( sizeof(gps.fix()) ); + DEBUG_PORT.print( F(" gps object size = ") ); + DEBUG_PORT.println( sizeof(gps) ); + DEBUG_PORT.println( F("Looking for GPS device on " GPS_PORT_NAME) ); + + #ifndef NMEAGPS_RECOGNIZE_ALL + #error You must define NMEAGPS_RECOGNIZE_ALL in NMEAGPS_cfg.h! + #endif + + #ifdef NMEAGPS_INTERRUPT_PROCESSING + #error You must *NOT* define NMEAGPS_INTERRUPT_PROCESSING in NMEAGPS_cfg.h! + #endif + + #if !defined( NMEAGPS_PARSE_GGA ) & !defined( NMEAGPS_PARSE_GLL ) & \ + !defined( NMEAGPS_PARSE_GSA ) & !defined( NMEAGPS_PARSE_GSV ) & \ + !defined( NMEAGPS_PARSE_RMC ) & !defined( NMEAGPS_PARSE_VTG ) & \ + !defined( NMEAGPS_PARSE_ZDA ) & !defined( NMEAGPS_PARSE_GST ) + + DEBUG_PORT.println( F("\nWARNING: No NMEA sentences are enabled: no fix data will be displayed.") ); + + #else + if (gps.merging == NMEAGPS::NO_MERGING) { + DEBUG_PORT.print ( F("\nWARNING: displaying data from ") ); + DEBUG_PORT.print ( gps.string_for( LAST_SENTENCE_IN_INTERVAL ) ); + DEBUG_PORT.print ( F(" sentences ONLY, and only if ") ); + DEBUG_PORT.print ( gps.string_for( LAST_SENTENCE_IN_INTERVAL ) ); + DEBUG_PORT.println( F(" is enabled.\n" + " Other sentences may be parsed, but their data will not be displayed.") ); + } + #endif + + DEBUG_PORT.print ( F("\nGPS quiet time is assumed to begin after a ") ); + DEBUG_PORT.print ( gps.string_for( LAST_SENTENCE_IN_INTERVAL ) ); + DEBUG_PORT.println( F(" sentence is received.\n" + " You should confirm this with NMEAorder.ino\n") ); + + trace_header( DEBUG_PORT ); + DEBUG_PORT.flush(); + + gpsPort.begin( 9600 ); +} + +//-------------------------- + +void loop() +{ + GPSloop(); +} diff --git a/software/firmware/libraries/NeoGPS/examples/NMEAGSV/NMEAGSV.ino b/software/firmware/libraries/NeoGPS/examples/NMEAGSV/NMEAGSV.ino new file mode 100644 index 0000000..08bb45e --- /dev/null +++ b/software/firmware/libraries/NeoGPS/examples/NMEAGSV/NMEAGSV.ino @@ -0,0 +1,107 @@ +#include + +NMEAGPS gps; // This parses the GPS characters +gps_fix fix; // This holds on to the latest values + +//====================================================================== +// Program: NMEAGSV.ino +// +// Description: Display satellites in view, as reported by the GSV sentences. +// +// Prerequisites: +// 1) NMEA.ino works with your device (correct TX/RX pins and baud rate) +// 2) NMEAGPS_PARSE_SATELLITES and NMEAGPS_PARSE_SATELLITE_INFO are +// enabled in NMEAGPS_cfg.h +// 3) The GSV sentence has been enabled in NMEAGPS_cfg.h. +// 4) Your device emits the GSV sentence (use NMEAorder.ino to confirm). +// 5) LAST_SENTENCE_IN_INTERVAL has been set to GSV (or any other enabled sentence) +// in NMEAGPS_cfg.h (use NMEAorder.ino). +// +// 'Serial' is for debug output to the Serial Monitor window. +// +// License: +// Copyright (C) 2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . +// +//====================================================================== + +#include + +//----------------- +// Check configuration + +#ifndef NMEAGPS_PARSE_GSV + #error You must define NMEAGPS_PARSE_GSV in NMEAGPS_cfg.h! +#endif + +#ifndef NMEAGPS_PARSE_SATELLITES + #error You must define NMEAGPS_PARSE_SATELLITE in NMEAGPS_cfg.h! +#endif + +#ifndef NMEAGPS_PARSE_SATELLITE_INFO + #error You must define NMEAGPS_PARSE_SATELLITE_INFO in NMEAGPS_cfg.h! +#endif + +//----------------- + +void setup() +{ + DEBUG_PORT.begin(9600); + while (!Serial) + ; + DEBUG_PORT.print( F("NeoGPS GSV example started\n") ); + + gpsPort.begin(9600); + +} // setup + +//----------------- + +void loop() +{ + while (gps.available( gpsPort )) { + fix = gps.read(); + + displaySatellitesInView(); + } + +} // loop + +//----------------- + +void displaySatellitesInView() +{ + DEBUG_PORT.print( gps.sat_count ); + DEBUG_PORT.print( ',' ); + + for (uint8_t i=0; i < gps.sat_count; i++) { + DEBUG_PORT.print( gps.satellites[i].id ); + DEBUG_PORT.print( ' ' ); + DEBUG_PORT.print( gps.satellites[i].elevation ); + DEBUG_PORT.print( '/' ); + DEBUG_PORT.print( gps.satellites[i].azimuth ); + DEBUG_PORT.print( '@' ); + if (gps.satellites[i].tracked) + DEBUG_PORT.print( gps.satellites[i].snr ); + else + DEBUG_PORT.print( '-' ); + DEBUG_PORT.print( F(", ") ); + } + + DEBUG_PORT.println(); + +} // displaySatellitesInView diff --git a/software/firmware/libraries/NeoGPS/examples/NMEASDlog/NMEASDlog.ino b/software/firmware/libraries/NeoGPS/examples/NMEASDlog/NMEASDlog.ino new file mode 100644 index 0000000..f4d1945 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/examples/NMEASDlog/NMEASDlog.ino @@ -0,0 +1,433 @@ +#include +#include + +//====================================================================== +// Program: NMEASDlog.ino +// +// Description: This program is an interrupt-driven GPS logger. +// It uses the alternative serial port libraries NeoHWSerial, +// NeoSWSerial, or NeoICSerial. +// +// Prerequisites: +// 1) You have completed the requirements for NMEA_isr.ino +// 2) You have connected an SPI SD card and verified it is working +// with other SD utilities. +// 3) For logging faster than the default 1Hz rate, you have +// identified the required commands for your GPS device. +// +// 'Serial' is for debug output to the Serial Monitor window. +// +// License: +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . +// +//====================================================================== + +#include + +//#include + +//---------------------------------------------------------------- +// Check configuration + +#if !defined( GPS_FIX_TIME ) || !defined( GPS_FIX_LOCATION ) + #error You must define TIME and LOCATION in GPSfix_cfg.h +#endif + +#if !defined( NMEAGPS_PARSE_RMC ) + #error You must define NMEAGPS_PARSE_RMC in NMEAGPS_cfg.h! +#endif + +#ifndef NMEAGPS_INTERRUPT_PROCESSING + #error You must define NMEAGPS_INTERRUPT_PROCESSING in NMEAGPS_cfg.h! +#endif + +static const int LED = 13; + +static NMEAGPS gps; + +//---------------------------------------------------------------- +// SD card includes and declarations + +#include +#include + +SdFat SD; +const int chipSelect = 8; + +//---------------------------------------------------------------- +// For testing, it may be more convenient to simply print the +// GPS fix fields to the Serial Monitor. Simply uncomment +// this define to skip all SD operations. An SD card module +// does not have to be connected. +#define SIMULATE_SD + +#ifdef SIMULATE_SD + + auto &logfile = DEBUG_PORT; + +#else + + File logfile; + +#endif + +//---------------------------------------------------------------- +// Utility to print a long integer like it's a float +// with 9 significant digits. + +void printL( Print & outs, int32_t degE7 ) +{ + // Extract and print negative sign + if (degE7 < 0) { + degE7 = -degE7; + outs.print( '-' ); + } + + // Whole degrees + int32_t deg = degE7 / 10000000L; + outs.print( deg ); + outs.print( '.' ); + + // Get fractional degrees + degE7 -= deg*10000000L; + + // Print leading zeroes, if needed + if (degE7 < 10L) + outs.print( F("000000") ); + else if (degE7 < 100L) + outs.print( F("00000") ); + else if (degE7 < 1000L) + outs.print( F("0000") ); + else if (degE7 < 10000L) + outs.print( F("000") ); + else if (degE7 < 100000L) + outs.print( F("00") ); + else if (degE7 < 1000000L) + outs.print( F("0") ); + + // Print fractional degrees + outs.print( degE7 ); +} + +//---------------------------------------------------------------- +// Because the SD write can take a long time, GPSisr will store +// parsed data in the NMEAGPS 'buffer' array until GPSloop can get to it. +// +// The number of elements you should have in the array depends on +// two things: the speed of your SD card, and the update rate you +// have chosen. +// +// For an update rate of 10Hz (100ms period), two fixes are probably +// enough. Most cards take ~100ms to complete a write of 512 bytes. +// With FIX_MAX=2, two complete fixes can be stored, which were +// received in 200ms. A third fix can be started, giving a little +// more time before an overrun occurs, a total of about 250ms. +// +// If your card is slower or your update rate is faster, you should +// first build and run this program to determine the speed of your +// card. The time it takes to log one record is printed to the log +// file. +// +// After the program has run for a minute or two, remove the +// card and examine the loggingTimes. You may see that an interval +// was skipped, and you will also see an OVERRUN message on the +// DEBUG_PORT (usually Serial). +// +// You should calculate a new FIX_MAX from the maximum loggingTime +// you see in the log file: +// +// FIX_MAX = (max loggingTime)/(update period) + 1; +// +// For example, if the max loggingTime is 160ms, and the update period is +// 100ms (10Hz), then FIX_MAX = 160/100 + 1 = 2. +// +// Change the FIX_MAX value, build and run the program again. The +// SD log file should now contain all records, and no OVERRUN +// messages should have been printed on the DEBUG_PORT. +// +// If you do see an OVERRUN message, examine the loggingTime to see +// if it exceeded the maximum value from the previous build, and +// increase FIX_MAX. +// +// If you are also printing data to a Serial device, you could be +// printing too much information. In general, you must print less than +// (baudrate/10) characters per second. For example, if your baudrate +// is 9600, you must print less than 960 characters per second. And if +// the update rate is 10Hz, you must print no more than 96 characters +// per update. +// +// There are also restrictions on how much you should print to Serial in one +// section of code. If you print more than 64 characters (the output buffer +// size), then some prints will block until all characters can be stored in the +// output buffer. +// +// For example, if you try to print 80 characters, the first 64 characters +// will be immediately stored in the output buffer. However, the last 16 +// characters must wait until the output buffer has room for 16 more +// characters. That takes 16 * (10/baudrate) milliseconds. At 9600 baud +// that will take 17ms. The loggingTimes will show no less than 17ms per +// record, and will occasionally include the longer SD write time of ~100ms. + +//---------------------------------------------------------------- + +static void GPSloop() +{ + if (gps.available()) { + + gps_fix fix = gps.read(); + + // Log the fix information if we have a location and time + + if (fix.valid.location && fix.valid.time) { + + static uint16_t lastLoggingTime = 0; + uint16_t startLoggingTime = millis(); + + // If you like the CSV format implemented in Streamers.h, + // you could replace all these prints with + // trace_all( logFile, fix ); // uncomment include Streamers.h + + printL( logfile, fix.latitudeL() ); + logfile.print( ',' ); + printL( logfile, fix.longitudeL() ); + logfile.print(','); + + if (fix.dateTime.hours < 10) + logfile.print( '0' ); + logfile.print(fix.dateTime.hours); + logfile.print( ':' ); + if (fix.dateTime.minutes < 10) + logfile.print( '0' ); + logfile.print(fix.dateTime.minutes); + logfile.print( ':' ); + if (fix.dateTime.seconds < 10) + logfile.print( '0' ); + logfile.print(fix.dateTime.seconds); + logfile.print( '.' ); + if (fix.dateTime_cs < 10) + logfile.print( '0' ); // leading zero for .05, for example + logfile.print(fix.dateTime_cs); + logfile.print(','); + + logfile.print( lastLoggingTime ); // write how long the previous logging took + logfile.println(); + + // flush() is used to empty the contents of the SD buffer to the SD. + // If you don't call flush, the data will fill up the SdFat buffer + // of 512bytes and flush itself automatically. + // + // To avoid losing data or corrupting the SD card file system, you must + // call flush() at least once (or close()) before powering down or pulling + // the SD card. + // + // It is *strongly* recommended that you use some external event + // to close the file. For example, staying within 50m of the moving + // average location for 1 minute, or using a switch to start and stop + // logging. It would also be good to provide a visual indication + // that it is safe to power down and/or remove the card, perhaps via + // the LED. + // + // To reduce the amount of data that may be lost by an abnormal shut down, + // you can call flush() periodically. + // + // Depending on the amount of data you are printing, you can save + // *a lot* of CPU time by not flushing too frequently. BTW, flushing + // every time at 5Hz is too frequent. + + // This shows how to flush once a second. + static uint16_t lastFlushTime = 0; + + if (startLoggingTime - lastFlushTime > 1000) { + lastFlushTime = startLoggingTime; // close enough + logfile.flush(); + } + + #ifdef SIMULATE_SD + // Simulate the delay of writing to an SD card. These times are + // very long. This is intended to show (and test) the overrun detection. + // + // On a 1Hz GPS, delaying more than 2 seconds here, or more than + // 2 seconds in two consecutive updates, will cause OVERRUN. + // + // Feel free to try different delays to simulate the actual behavior + // of your SD card. + + uint16_t t = random(0,5); // 0..4 + t += 3; // 3..7 + t = t*t*t*t; // 81..2401ms + delay( t ); // cause an OVERRUN + #endif + + // All logging is finished, figure out how long that took. + // This will be written in the *next* record. + lastLoggingTime = (uint16_t) millis() - startLoggingTime; + } + } + +} // GPSloop + +//---------------------------------------------------------------- + +void GPSisr( uint8_t c ) +{ + gps.handle( c ); + +} // GPSisr + +//---------------------------------------------------------------- +// This routine waits for GPSisr to provide +// a fix that has a valid location. +// +// The LED is slowly flashed while it's waiting. + +static void waitForFix() +{ + DEBUG_PORT.print( F("Waiting for GPS fix...") ); + + uint16_t lastToggle = millis(); + + for (;;) { + if (gps.available()) { + if (gps.read().valid.location) + break; // Got it! + } + + // Slowly flash the LED until we get a fix + if ((uint16_t) millis() - lastToggle > 500) { + lastToggle += 500; + digitalWrite( LED, !digitalRead(LED) ); + DEBUG_PORT.write( '.' ); + } + } + DEBUG_PORT.println(); + + digitalWrite( LED, LOW ); + + gps.overrun( false ); // we had to wait a while... + +} // waitForFix + +//---------------------------------------------------------------- + +void setup() +{ + DEBUG_PORT.begin(9600); + while (!DEBUG_PORT) + ; // wait for serial port to connect. + + DEBUG_PORT.println( F("NMEASDlog.ino started!") ); + DEBUG_PORT.print( F("fix size = ") ); + DEBUG_PORT.println( sizeof(gps_fix) ); + DEBUG_PORT.print( NMEAGPS_FIX_MAX ); + DEBUG_PORT.println( F(" GPS updates can be buffered.") ); + + if (gps.merging != NMEAGPS::EXPLICIT_MERGING) + DEBUG_PORT.println( F("Warning: EXPLICIT_MERGING should be enabled for best results!") ); + + gpsPort.attachInterrupt( GPSisr ); + gpsPort.begin( 9600 ); + + // Configure the GPS. These are commands for MTK GPS devices. Other + // brands will have different commands. + gps.send_P( &gpsPort, F("PMTK314,0,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0") ); // RMC only for MTK GPS devices + gps.send_P( &gpsPort, F("PMTK220,100") ); // 10Hz update rate for MTK GPS devices + + // Enable the LED for blinking feedback + pinMode( LED, OUTPUT ); + + initSD(); + + waitForFix(); + +} // setup + +//---------------------------------------------------------------- + +void loop() +{ + GPSloop(); + + if (gps.overrun()) { + gps.overrun( false ); + DEBUG_PORT.println( F("DATA OVERRUN: fix data lost!") ); + } +} + +//---------------------------------------------------------------- + +void initSD() +{ + #ifdef SIMULATE_SD + + DEBUG_PORT.println( F(" Simulating SD.") ); + + #else + + DEBUG_PORT.println( F("Initializing SD card...") ); + + // see if the card is present and can be initialized: + if (!SD.begin(chipSelect)) { + DEBUG_PORT.println( F(" SD card failed, or not present") ); + // don't do anything more: + + // Flicker the LED + while (true) { + digitalWrite(LED,HIGH); + delay(75); + digitalWrite(LED,LOW); + delay(75); + } + } + + DEBUG_PORT.println( F(" SD card initialized.") ); + + // Pick a numbered filename, 00 to 99. + char filename[15] = "data_##.txt"; + + for (uint8_t i=0; i<100; i++) { + filename[5] = '0' + i/10; + filename[6] = '0' + i%10; + if (!SD.exists(filename)) { + // Use this one! + break; + } + } + + logfile = SD.open(filename, FILE_WRITE); + if (!logfile) { + DEBUG_PORT.print( F("Couldn't create ") ); + DEBUG_PORT.println(filename); + + // If the file can't be created for some reason this leaves the LED on + // so I know there is a problem + digitalWrite(LED,HIGH); + + while (true) {} + } + + DEBUG_PORT.print( F("Writing to ") ); + DEBUG_PORT.println(filename); + + // GPS Visualizer requires a header to identify the CSV fields. + // If you are saving other data or don't need this, simply remove/change it + logfile.println( F("latitude,longitude,time,loggingTime") ); + + //trace_header( logfile ); // and uncomment #include Streamers.h + + #endif +} // initSD \ No newline at end of file diff --git a/software/firmware/libraries/NeoGPS/examples/NMEA_isr/NMEA_isr.ino b/software/firmware/libraries/NeoGPS/examples/NMEA_isr/NMEA_isr.ino new file mode 100644 index 0000000..2c6a1fb --- /dev/null +++ b/software/firmware/libraries/NeoGPS/examples/NMEA_isr/NMEA_isr.ino @@ -0,0 +1,90 @@ +#include + +//====================================================================== +// Program: NMEA_isr.ino +// +// Prerequisites: +// 1) NMEA.ino works with your device +// +// Description: This minimal program parses the GPS data during the +// RX character interrupt. The ISR passes the character to +// the GPS object for parsing. The GPS object will add gps_fix +// structures to a buffer that can be later read() by loop(). +// +// License: +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . +// +//====================================================================== + +#include + +#include + +// Check configuration + +#ifndef NMEAGPS_INTERRUPT_PROCESSING + #error You must define NMEAGPS_INTERRUPT_PROCESSING in NMEAGPS_cfg.h! +#endif + +static NMEAGPS gps; + +//-------------------------- + +static void GPSisr( uint8_t c ) +{ + gps.handle( c ); + +} // GPSisr + +//-------------------------- + +void setup() +{ + DEBUG_PORT.begin(9600); + while (!DEBUG_PORT) + ; + + DEBUG_PORT.print( F("NMEA_isr.INO: started\n") ); + DEBUG_PORT.print( F("fix object size = ") ); + DEBUG_PORT.println( sizeof(gps.fix()) ); + DEBUG_PORT.print( F("NMEAGPS object size = ") ); + DEBUG_PORT.println( sizeof(gps) ); + DEBUG_PORT.println( F("Looking for GPS device on " GPS_PORT_NAME) ); + + trace_header( DEBUG_PORT ); + + DEBUG_PORT.flush(); + + gpsPort.attachInterrupt( GPSisr ); + gpsPort.begin( 9600 ); +} + +//-------------------------- + +void loop() +{ + if (gps.available()) { + // Print all the things! + trace_all( DEBUG_PORT, gps, gps.read() ); + } + + if (gps.overrun()) { + gps.overrun( false ); + DEBUG_PORT.println( F("DATA OVERRUN: took too long to print GPS data!") ); + } +} diff --git a/software/firmware/libraries/NeoGPS/examples/NMEAaverage/NMEAaverage.ino b/software/firmware/libraries/NeoGPS/examples/NMEAaverage/NMEAaverage.ino new file mode 100644 index 0000000..a8012dc --- /dev/null +++ b/software/firmware/libraries/NeoGPS/examples/NMEAaverage/NMEAaverage.ino @@ -0,0 +1,265 @@ +#include + +//====================================================================== +// Program: NMEAaverage.ino +// +// Description: This program averages locations over time to compute +// a higher-accuracy *static* location. It also shows +// how to use the distance functions in the Location class. +// +// Prerequisites: +// 1) NMEA.ino works with your device (correct TX/RX pins and baud rate) +// 2) At least once sentence with a location field has been enabled +// +// 'Serial' is for debug output to the Serial Monitor window. +// +// License: +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . +// +//====================================================================== + +#include + +//------------------------------------------------------------ +// Check that the config files are set up properly + +#if !defined( NMEAGPS_PARSE_GGA ) && \ + !defined( NMEAGPS_PARSE_GLL ) && \ + !defined( NMEAGPS_PARSE_RMC ) + #error You must uncomment at least one of NMEAGPS_PARSE_GGA, GGL or RMC in NMEAGPS_cfg.h! +#endif + +#if !defined( GPS_FIX_LOCATION ) + #error You must uncomment GPS_FIX_LOCATION in GPSfix_cfg.h! +#endif + +#if !defined( GPS_FIX_TIME ) + #error You must uncomment GPS_FIX_TIME in GPSfix_cfg.h! +#endif + +#if !defined( GPS_FIX_DATE ) + #error You must uncomment GPS_FIX_DATE in GPSfix_cfg.h! +#endif + +//------------------------------------------------------------ + +static NMEAGPS gps; // This parses the GPS characters +static gps_fix fix; // This holds the latest GPS fix + +//------------------------------------------------------------ + +using namespace NeoGPS; +static gps_fix first; // good GPS data +static clock_t firstSecs; // cached dateTime in seconds since EPOCH +static Location_t avgLoc; // gradually-calculated average location +static uint16_t count; // number of samples +static int32_t sumDLat, sumDLon; // accumulated deltas +static bool doneAccumulating; // accumulation completed + +//------------------------------------------------------------ + +const char nCD [] PROGMEM = "N"; +const char nneCD[] PROGMEM = "NNE"; +const char neCD [] PROGMEM = "NE"; +const char eneCD[] PROGMEM = "ENE"; +const char eCD [] PROGMEM = "E"; +const char eseCD[] PROGMEM = "ESE"; +const char seCD [] PROGMEM = "SE"; +const char sseCD[] PROGMEM = "SSE"; +const char sCD [] PROGMEM = "S"; +const char sswCD[] PROGMEM = "SSW"; +const char swCD [] PROGMEM = "SW"; +const char wswCD[] PROGMEM = "WSW"; +const char wCD [] PROGMEM = "W"; +const char wnwCD[] PROGMEM = "WNW"; +const char nwCD [] PROGMEM = "NW"; +const char nnwCD[] PROGMEM = "NNW"; + +const char * const dirStrings[] PROGMEM = + { nCD, nneCD, neCD, eneCD, eCD, eseCD, seCD, sseCD, + sCD, sswCD, swCD, wswCD, wCD, wnwCD, nwCD, nnwCD }; + +const __FlashStringHelper *compassDir( uint16_t bearing ) // degrees CW from N +{ + const int16_t directions = sizeof(dirStrings)/sizeof(dirStrings[0]); + const int16_t degreesPerDir = 360 / directions; + int8_t dir = (bearing + degreesPerDir/2) / degreesPerDir; + + while (dir < 0) + dir += directions; + while (dir >= directions) + dir -= directions; + + return (const __FlashStringHelper *) pgm_read_ptr( &dirStrings[ dir ] ); + +} // compassDir + +//------------------------------------------------------------ + +static void doSomeWork() +{ + static bool warned = false; // that we're waiting for a valid location + + if (fix.valid.location && fix.valid.date && fix.valid.time) { + + if (count == 0) { + + // Just save the first good fix + first = fix; + firstSecs = (clock_t) first.dateTime; + count = 1; + + } else { + + // After the first fix, accumulate locations until we have + // a good average. Then display the offset from the average. + + if (warned) { + // We were waiting for the fix to be re-acquired. + warned = false; + DEBUG_PORT.println(); + } + + DEBUG_PORT.print( count ); + + if (!doneAccumulating) { + + // Enough time? + if (((clock_t)fix.dateTime - firstSecs) > 2 * SECONDS_PER_HOUR) + doneAccumulating = true; + } + + int32_t dLat, dLon; + + if (!doneAccumulating) { + + // Use deltas from the first location + dLat = fix.location.lat() - first.location.lat(); + sumDLat += dLat; + int32_t avgDLat = sumDLat / count; + + dLon = fix.location.lon() - first.location.lon(); + sumDLon += dLon; + int32_t avgDLon = sumDLon / count; + + // Then calculated the average location as the first location + // plus the averaged deltas. + avgLoc.lat( first.location.lat() + avgDLat ); + avgLoc.lon( first.location.lon() + avgDLon ); + + count++; + } + + DEBUG_PORT.print( ',' ); + DEBUG_PORT.print( avgLoc.lat() ); + DEBUG_PORT.print( ',' ); + DEBUG_PORT.print( avgLoc.lon() ); + DEBUG_PORT.print( ',' ); + dLat = avgLoc.lat() - fix.location.lat(); + DEBUG_PORT.print( dLat ); + DEBUG_PORT.print( ',' ); + dLon = avgLoc.lon() - fix.location.lon(); + DEBUG_PORT.print( dLon ); + + // Calculate the distance from the current fix to the average location + float avgDistError = avgLoc.DistanceKm( fix.location ); + DEBUG_PORT.print( ',' ); + DEBUG_PORT.print( avgDistError * 100000.0 ); // cm + + // Calculate the bearing from the current fix to the average location. + // NOTE: other libraries will have trouble with this calculation, + // because these coordinates are *VERY* close together. Naive + // floating-point calculations will not have enough significant + // digits. + float avgBearingErr = fix.location.BearingTo( avgLoc ); + float bearing = avgBearingErr * Location_t::DEG_PER_RAD; + DEBUG_PORT.print( ',' ); + DEBUG_PORT.print( bearing, 6 ); + DEBUG_PORT.print( ',' ); + DEBUG_PORT.print( compassDir( bearing ) ); + + // Calculate a point that is 10km away from the average location, + // at the error bearing + Location_t tenKmAway( avgLoc ); + tenKmAway.OffsetBy( 10.0 / Location_t::EARTH_RADIUS_KM, avgBearingErr ); + DEBUG_PORT.print( ',' ); + DEBUG_PORT.print( tenKmAway.lat() ); + DEBUG_PORT.print( ',' ); + DEBUG_PORT.print( tenKmAway.lon() ); + + // Calculate the bearing from the average location to that point. + // This should be very close to the avgBearingErr, and will + // reflect the calculation error. This is because the + // current fix is *VERY* close to the average location. + float tb = avgLoc.BearingToDegrees( tenKmAway ); + DEBUG_PORT.print( ',' ); + DEBUG_PORT.print( tb, 6 ); + + DEBUG_PORT.println(); + } + + } else { + if (!warned) { + warned = true; + DEBUG_PORT.print( F("Waiting for fix...") ); + } else { + DEBUG_PORT.print( '.' ); + } + } + +} // doSomeWork + +//------------------------------------------------------------ + +static void GPSloop() +{ + while (gps.available( gpsPort )) { + fix = gps.read(); + doSomeWork(); + } + +} // GPSloop + +//------------------------------------------------------------ + +void setup() +{ + DEBUG_PORT.begin(9600); + while (!DEBUG_PORT) + ; + + DEBUG_PORT.print( F("NMEAaverage.INO: started\n") ); + DEBUG_PORT.print( F(" fix object size = ") ); + DEBUG_PORT.println( sizeof(gps.fix()) ); + DEBUG_PORT.print( F(" gps object size = ") ); + DEBUG_PORT.println( sizeof(gps) ); + DEBUG_PORT.println( F("Looking for GPS device on " GPS_PORT_NAME) ); + DEBUG_PORT.println( F("Comparing current fix with averaged location.\n" + "count,avg lat,avg lon,dlat,dlon,distance(cm)," + "bearing deg,compass,lat/lon 10km away & recalc bearing") ); + DEBUG_PORT.flush(); + + gpsPort.begin( 9600 ); +} + +//------------------------------------------------------------ + +void loop() +{ + GPSloop(); +} diff --git a/software/firmware/libraries/NeoGPS/examples/NMEAbenchmark/NMEAbenchmark.ino b/software/firmware/libraries/NeoGPS/examples/NMEAbenchmark/NMEAbenchmark.ino new file mode 100644 index 0000000..0284b4e --- /dev/null +++ b/software/firmware/libraries/NeoGPS/examples/NMEAbenchmark/NMEAbenchmark.ino @@ -0,0 +1,105 @@ +#include + +//====================================================================== +// Program: NMEAbenchmark.ino +// +// Prerequisites: +// +// Description: Use GPGGA and GPRMC sentences to test +// the parser's performance. +// +// GSV sentences are tested if enabled. +// +// 'Serial' is for debug output to the Serial Monitor window. +// +// License: +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . +// +//====================================================================== + +#include + +static NMEAGPS gps; + +//-------------------------- + +static uint32_t time_it( const char *data ) +{ + const uint16_t ITERATIONS = 1024; + uint32_t start, end; + + Serial.flush(); + start = micros(); + for (uint16_t i=ITERATIONS; i > 0; i--) { + char *ptr = (char *) data; + while (*ptr) + gps.decode( *ptr++ ); + } + end = micros(); + + return (end-start)/ITERATIONS; +} + +//-------------------------- + +void setup() +{ + Serial.begin(9600); + Serial.println( F("NMEAbenchmark: started") ); + Serial.print( F("fix object size = ") ); + Serial.println( sizeof(gps.fix()) ); + Serial.print( F(" gps object size = ") ); + Serial.println( sizeof(gps) ); + + trace_header( Serial ); + + Serial.flush(); + + const char *gga = + "$GPGGA,092725.00,4717.11399,N,00833.91590,E," + "1,8,1.01,499.6,M,48.0,M,,0*5B\r\n"; + const char *gga_no_lat = + "$GPGGA,092725.00,,,00833.91590,E," + "1,8,1.01,499.6,M,48.0,M,,0*0D\r\n"; + + Serial << F("GGA time = ") << time_it( gga ) << '\n'; + trace_all( Serial, gps, gps.fix() ); + + Serial << F("GGA no lat time = ") << time_it( gga_no_lat ) << '\n'; + trace_all( Serial, gps, gps.fix() ); + + const char *rmc = + "$GPRMC,083559.00,A,4717.11437,N,00833.91522,E," + "0.004,77.52,091202,,,A*57\r\n"; + + Serial << F("RMC time = ") << time_it( rmc ) << '\n'; + trace_all( Serial, gps, gps.fix() ); + + #ifdef NMEAGPS_PARSE_GSV + const char *gsv = + "$GPGSV,3,1,10,23,38,230,44,29,71,156,47,07,29,116,41,08,09,081,36*7F\r\n" + "$GPGSV,3,2,10,10,07,189,,05,05,220,,09,34,274,42,18,25,309,44*72\r\n" + "$GPGSV,3,3,10,26,82,187,47,28,43,056,46*77\r\n"; + Serial << F("GSV time = ") << time_it( gsv ) << '\n'; + trace_all( Serial, gps, gps.fix() ); + #endif +} + +//-------------------------- + +void loop() {} diff --git a/software/firmware/libraries/NeoGPS/examples/NMEAblink/NMEAblink.ino b/software/firmware/libraries/NeoGPS/examples/NMEAblink/NMEAblink.ino new file mode 100644 index 0000000..24b1583 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/examples/NMEAblink/NMEAblink.ino @@ -0,0 +1,69 @@ +#include + +//====================================================================== +// Program: NMEAblink.ino +// +// Prerequisites: +// 1) NMEA.ino works with your device +// +// Description: This program will toggle the LED once per second, +// when the LAST_SENTENCE_IN_INTERVAL is received. +// +// Because no actual GPS data is used, you could disable all +// messages (except the LAST_SENTENCE) and all gps_fix members. +// It would still receive a 'fix' oncer per second, without +// without using any RAM or CPU time to parse or save +// the (unused) values. Essentially, this app uses the LAST_SENTENCE +// as a 1PPS signal. +// +// Note: Because this example does not use 'Serial', you +// could use 'Serial' for the gpsPort, like this: +// +// #define gpsPort Serial +// +// See GPSport.h for more information. +// +// License: +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . +// +//====================================================================== + +#include + +static NMEAGPS gps; +static const int led = 13; + +//-------------------------- + +void setup() +{ + gpsPort.begin(9600); + + pinMode(led, OUTPUT); +} + +//-------------------------- + +void loop() +{ + if (gps.available( gpsPort)) { + gps.read(); // don't really do anything with the fix... + + digitalWrite( led, !digitalRead(led) ); // toggle the LED + } +} diff --git a/software/firmware/libraries/NeoGPS/examples/NMEAdiagnostic/NMEAdiagnostic.ino b/software/firmware/libraries/NeoGPS/examples/NMEAdiagnostic/NMEAdiagnostic.ino new file mode 100644 index 0000000..8fc8842 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/examples/NMEAdiagnostic/NMEAdiagnostic.ino @@ -0,0 +1,367 @@ +#include + +//====================================================================== +// Program: NMEAdiagnostic.ino +// +// Description: This program tries different baud rates until +// valid NMEA sentences are detected. Some GPS devices may +// have a binary mode that does not emit NMEA sentences. You +// may have to send a special command or use a utility program +// to configure it to emit NMEA sentences instead of binary messages. +// +// Prerequisites: +// 1) Your GPS device has been correctly powered. +// Be careful when connecting 3.3V devices. +// 2) Your GPS device is correctly connected to an Arduino serial port. +// See GPSport.h for the default connections. +// +// 'Serial' is for debug output to the Serial Monitor window. +// +// License: +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . +// +//====================================================================== + +#include +#include + +// Check configuration + +#ifndef NMEAGPS_RECOGNIZE_ALL + #error You must define NMEAGPS_RECOGNIZE_ALL in NMEAGPS_cfg.h! +#endif + +#ifdef NMEAGPS_IMPLICIT_MERGING + #error You must *undefine* NMEAGPS_IMPLICIT_MERGING in NMEAGPS_cfg.h! \ + Please use EXPLICIT or NO_MERGING. +#endif + +#ifdef NMEAGPS_INTERRUPT_PROCESSING + #error You must *NOT* define NMEAGPS_INTERRUPT_PROCESSING in NMEAGPS_cfg.h! +#endif + +static NMEAGPS gps ; // This parses received characters +static gps_fix all_data ; // A composite of all GPS data fields +static uint32_t last_rx = 0UL; // The last millis() time a character was + // received from GPS. +static uint32_t valid_sentence_received = 0UL; +static bool last_sentence_received = false; +static uint32_t baudStartTime = 0UL; +static uint8_t warnings = 0; +static uint8_t errors = 0; + +//-------------------------- + +static void hang() +{ + DEBUG_PORT.println( F("\n** NMEAdiagnostic completed **\n") ); + + if (warnings) { + DEBUG_PORT.print( warnings ); + DEBUG_PORT.print( F(" warnings") ); + } + if (warnings && errors) + DEBUG_PORT.print( F(" and ") ); + if (errors) { + DEBUG_PORT.print( errors ); + DEBUG_PORT.print( F(" errors") ); + } + if (warnings || errors) + DEBUG_PORT.println(); + + DEBUG_PORT.flush(); + + for (;;) + ; + +} // hang + +//-------------------------- +// Baud rates to check + +static long baud_table[] = + { 1200, 2400, 4800, 9600, 14400, 19200, 28800, 31250, 38400, + 57600, 115200 }; +static const uint8_t num_bauds = sizeof(baud_table)/sizeof(baud_table[0]); +static const uint8_t INITIAL_BAUD_INDEX = 3; // 9600 +static uint8_t baud_index = INITIAL_BAUD_INDEX; +static bool triedDifferentBaud = false; + +//-------------------------- + +static void tryBaud() +{ + long baud = baud_table[baud_index]; + DEBUG_PORT.print( F("\n____________________________\n\nChecking ") ); + DEBUG_PORT.print( baud ); + DEBUG_PORT.print( F(" baud...\n") ); + DEBUG_PORT.flush(); + +//if (baud == 9600) baud = 17000; + gpsPort.begin( baud ); + baudStartTime = millis(); + +} // tryBaud + +//-------------------------- + +static void tryAnotherBaudRate() +{ + gpsPort.end(); + while (gpsPort.available()) + gpsPort.read(); + + if (baud_index == INITIAL_BAUD_INDEX) { + baud_index = 0; + + } else { + baud_index++; + if (baud_index == INITIAL_BAUD_INDEX) + baud_index++; // skip it, we already tried it + + if (baud_index >= num_bauds) { + baud_index = INITIAL_BAUD_INDEX; + DEBUG_PORT.print( F("\n All baud rates tried!\n") ); + hang(); + } + } + + tryBaud(); + + triedDifferentBaud = true; + +} // tryAnotherBaudRate + +//------------------------------------ + +static const uint16_t MAX_SAMPLE = 256; +static uint8_t someChars[ MAX_SAMPLE ]; +static uint16_t someCharsIndex = 0; + +static void dumpSomeChars() +{ + if (someCharsIndex > 0) { + DEBUG_PORT.print( F("Received data:\n") ); + + const uint16_t bytes_per_line = 32; + char ascii[ bytes_per_line ]; + uint8_t *ptr = &someChars[0]; + + for (uint16_t i=0; i 1000UL; + + if ((ms_since_last_rx > 5) && waited_long_enough) { + + // The GPS device has not sent any characters for at least 5ms. + // See if we've been getting chars sometime during the last second. + // If not, the GPS may not be working or connected properly. + + bool getting_chars = (someCharsIndex > 0); + + // Try to diagnose the problem + + static uint8_t tries = 1; + bool tryNext = false; + + if (!getting_chars) { + + if (tries++ >= 3) { + errors++; + DEBUG_PORT.println( F("\nCheck GPS device and/or connections. No data received.\n") ); + tryNext = true; + } + + } else if (valid_sentence_received) { + uint8_t s = valid_sentence_received/1000; + uint8_t ms = valid_sentence_received - s*1000; + + DEBUG_PORT.print( F("Valid sentences were received ") ); + DEBUG_PORT.print( s ); + DEBUG_PORT.print( '.' ); + if (ms < 100) + DEBUG_PORT.print( '0' ); + if (ms < 10) + DEBUG_PORT.print( '0' ); + DEBUG_PORT.print( ms ); + DEBUG_PORT.println( + F(" seconds ago.\n" + " The GPS update rate may be lower than 1Hz,\n" + " or the connections may be bad." ) ); + displaySentences(); + hang(); + + } else { + DEBUG_PORT.println( + F("No valid sentences, but characters are being received.\n" + " Check baud rate or device protocol configuration.\n" ) ); + + dumpSomeChars(); + delay( 2000 ); + tryNext = true; + } + + if (tryNext) { + tries = 1; + tryAnotherBaudRate(); + valid_sentence_received = 0UL; + } + } + +} // listenForSomething + +//------------------------------------ + +static void GPSloop() +{ + while (gpsPort.available()) { + last_rx = millis(); + + uint8_t c = gpsPort.read(); + + if (someCharsIndex < MAX_SAMPLE) + someChars[ someCharsIndex++ ] = c; + + if (gps.decode( c ) == NMEAGPS::DECODE_COMPLETED) { + all_data |= gps.fix(); + valid_sentence_received = last_rx; + + if (gps.nmeaMessage == LAST_SENTENCE_IN_INTERVAL) + last_sentence_received = true; + + DEBUG_PORT.print( F("Received ") ); + DEBUG_PORT.println( gps.string_for( gps.nmeaMessage ) ); + + static uint8_t sentences_printed = 0; + bool long_enough = (millis() - baudStartTime > 3000); + + if (long_enough || + ( + (sentences_printed++ >= 20) && + (someCharsIndex >= MAX_SAMPLE) + ) ) { + displaySentences(); + hang(); + } + } + } + + if (!valid_sentence_received || + (millis() - valid_sentence_received > 3000UL)) + listenForSomething(); + +} // GPSloop + +//-------------------------- + +void setup() +{ + DEBUG_PORT.begin(9600); + while (!DEBUG_PORT) + ; + + DEBUG_PORT.print( F("NMEAdiagnostic.INO: started\n") ); + DEBUG_PORT.println( F("Looking for GPS device on " GPS_PORT_NAME) ); + + if (sizeof(gps_fix) <= 2) { + warnings++; + DEBUG_PORT.print( F("\nWarning: no fields are enabled in GPSfix_cfg.h.\n Only the following information will be displayed:\n ") ); + trace_header( DEBUG_PORT ); + } + + #if !defined( NMEAGPS_PARSE_GGA ) & !defined( NMEAGPS_PARSE_GLL ) & \ + !defined( NMEAGPS_PARSE_GSA ) & !defined( NMEAGPS_PARSE_GSV ) & \ + !defined( NMEAGPS_PARSE_RMC ) & !defined( NMEAGPS_PARSE_VTG ) & \ + !defined( NMEAGPS_PARSE_ZDA ) & !defined( NMEAGPS_PARSE_GST ) + warnings++; + DEBUG_PORT.println( F("\nWarning: no messages are enabled for parsing in NMEAGPS_cfg.h.\n No fields will be valid, including the 'status' field.") ); + #endif + + DEBUG_PORT.flush(); + + tryBaud(); + +} // setup + +//-------------------------- + +void loop() +{ + GPSloop(); +} diff --git a/software/firmware/libraries/NeoGPS/examples/NMEAdistance/NMEAdistance.ino b/software/firmware/libraries/NeoGPS/examples/NMEAdistance/NMEAdistance.ino new file mode 100644 index 0000000..40d559b --- /dev/null +++ b/software/firmware/libraries/NeoGPS/examples/NMEAdistance/NMEAdistance.ino @@ -0,0 +1,82 @@ +#include + +//====================================================================== +// Program: NMEAdistance.ino +// +// Description: Display distance from a base location. +// +// Prerequisites: +// 1) NMEA.ino works with your device (correct TX/RX pins and baud rate) +// 2) GPS_FIX_LOCATION has been enabled. +// 3) A sentence that contains lat/long has been enabled (GGA, GLL or RMC). +// 4) Your device sends at least one of those sentences. +// +// 'Serial' is for debug output to the Serial Monitor window. +// +// License: +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . +// +//====================================================================== + +#include + +//------------------------------------------------------------ +// Check that the config files are set up properly + +#if !defined( NMEAGPS_PARSE_RMC ) & \ + !defined( NMEAGPS_PARSE_GGA ) & \ + !defined( NMEAGPS_PARSE_GLL ) + #error You must uncomment at least one of NMEAGPS_PARSE_RMC, NMEAGPS_PARSE_GGA or NMEAGPS_PARSE_GLL in NMEAGPS_cfg.h! +#endif + +#if !defined( GPS_FIX_LOCATION ) + #error You must uncomment GPS_FIX_LOCATION in GPSfix_cfg.h! +#endif + +NMEAGPS gps; + +// The base location, in degrees * 10,000,000 +NeoGPS::Location_t base( -253448688L, 1310324914L ); // Ayers Rock, AU + +void setup() +{ + DEBUG_PORT.begin(9600); + DEBUG_PORT.println( F("NMEAdistance.ino started.") ); + DEBUG_PORT.println( F("Looking for GPS device on " GPS_PORT_NAME) ); + + gpsPort.begin(9600); + +} // setup + +void loop() +{ + while (gps.available( gpsPort )) { + gps_fix fix = gps.read(); // save the latest + + // When we have a location, calculate how far away we are from the base location. + if (fix.valid.location) { + float range = fix.location.DistanceMiles( base ); + + DEBUG_PORT.print( F("Range: ") ); + DEBUG_PORT.print( range ); + DEBUG_PORT.println( F(" Miles") ); + } else + // Waiting... + DEBUG_PORT.print( '.' ); + } +} // loop diff --git a/software/firmware/libraries/NeoGPS/examples/NMEAloc/NMEAloc.ino b/software/firmware/libraries/NeoGPS/examples/NMEAloc/NMEAloc.ino new file mode 100644 index 0000000..67750e7 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/examples/NMEAloc/NMEAloc.ino @@ -0,0 +1,183 @@ +#include + +//====================================================================== +// Program: NMEAloc.ino +// +// Description: This program only parses an RMC sentence for the lat/lon. +// +// Prerequisites: +// 1) NMEA.ino works with your device (correct TX/RX pins and baud rate) +// 2) The RMC sentence has been enabled. +// 3) Your device sends an RMC sentence (e.g., $GPRMC). +// +// 'Serial' is for debug output to the Serial Monitor window. +// +// License: +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . +// +//====================================================================== + +#include + +//------------------------------------------------------------ +// Check that the config files are set up properly + +#if !defined( NMEAGPS_PARSE_RMC ) + #error You must uncomment NMEAGPS_PARSE_RMC in NMEAGPS_cfg.h! +#endif + +#if !defined( GPS_FIX_TIME ) + #error You must uncomment GPS_FIX_TIME in GPSfix_cfg.h! +#endif + +#if !defined( GPS_FIX_LOCATION ) + #error You must uncomment GPS_FIX_LOCATION in GPSfix_cfg.h! +#endif + +#if !defined( GPS_FIX_SPEED ) + #error You must uncomment GPS_FIX_SPEED in GPSfix_cfg.h! +#endif + +#if !defined( GPS_FIX_SATELLITES ) + #error You must uncomment GPS_FIX_SATELLITES in GPSfix_cfg.h! +#endif + +#ifdef NMEAGPS_INTERRUPT_PROCESSING + #error You must *NOT* define NMEAGPS_INTERRUPT_PROCESSING in NMEAGPS_cfg.h! +#endif + +//------------------------------------------------------------ + +static NMEAGPS gps; // This parses the GPS characters + +//---------------------------------------------------------------- +// Print the 32-bit integer degrees *as if* they were high-precision floats + +static void printL( Print & outs, int32_t degE7 ); +static void printL( Print & outs, int32_t degE7 ) +{ + // Extract and print negative sign + if (degE7 < 0) { + degE7 = -degE7; + outs.print( '-' ); + } + + // Whole degrees + int32_t deg = degE7 / 10000000L; + outs.print( deg ); + outs.print( '.' ); + + // Get fractional degrees + degE7 -= deg*10000000L; + + // Print leading zeroes, if needed + int32_t factor = 1000000L; + while ((degE7 < factor) && (factor > 1L)){ + outs.print( '0' ); + factor /= 10L; + } + + // Print fractional degrees + outs.print( degE7 ); +} + +static void doSomeWork( const gps_fix & fix ); +static void doSomeWork( const gps_fix & fix ) +{ + // This is the best place to do your time-consuming work, right after + // the RMC sentence was received. If you do anything in "loop()", + // you could cause GPS characters to be lost, and you will not + // get a good lat/lon. + // For this example, we just print the lat/lon. If you print too much, + // this routine will not get back to "loop()" in time to process + // the next set of GPS data. + + if (fix.valid.location) { + + if ( fix.dateTime.seconds < 10 ) + DEBUG_PORT.print( '0' ); + DEBUG_PORT.print( fix.dateTime.seconds ); + DEBUG_PORT.print( ',' ); + + // DEBUG_PORT.print( fix.latitude(), 6 ); // floating-point display + // DEBUG_PORT.print( fix.latitudeL() ); // integer display + printL( DEBUG_PORT, fix.latitudeL() ); // prints int like a float + DEBUG_PORT.print( ',' ); + // DEBUG_PORT.print( fix.longitude(), 6 ); // floating-point display + // DEBUG_PORT.print( fix.longitudeL() ); // integer display + printL( DEBUG_PORT, fix.longitudeL() ); // prints int like a float + + DEBUG_PORT.print( ',' ); + if (fix.valid.satellites) + DEBUG_PORT.print( fix.satellites ); + + DEBUG_PORT.print( ',' ); + DEBUG_PORT.print( fix.speed(), 6 ); + DEBUG_PORT.print( F(" kn = ") ); + DEBUG_PORT.print( fix.speed_mph(), 6 ); + DEBUG_PORT.print( F(" mph") ); + + } else { + // No valid location data yet! + DEBUG_PORT.print( '?' ); + } + + DEBUG_PORT.println(); + +} // doSomeWork + +//------------------------------------ + +static void GPSloop(); +static void GPSloop() +{ + while (gps.available( gpsPort )) + doSomeWork( gps.read() ); + +} // GPSloop + +//-------------------------- + +void setup() +{ + DEBUG_PORT.begin(9600); + while (!DEBUG_PORT) + ; + + DEBUG_PORT.print( F("NMEAloc.INO: started\n") ); + DEBUG_PORT.print( F("fix object size = ") ); + DEBUG_PORT.println( sizeof(gps.fix()) ); + DEBUG_PORT.print( F("NMEAGPS object size = ") ); + DEBUG_PORT.println( sizeof(gps) ); + DEBUG_PORT.println( F("Looking for GPS device on " GPS_PORT_NAME) ); + + #ifdef NMEAGPS_NO_MERGING + DEBUG_PORT.println( F("Only displaying data from xxRMC sentences.\n Other sentences may be parsed, but their data will not be displayed.") ); + #endif + + DEBUG_PORT.flush(); + + gpsPort.begin(9600); +} + +//-------------------------- + +void loop() +{ + GPSloop(); +} diff --git a/software/firmware/libraries/NeoGPS/examples/NMEAlocDMS/NMEAlocDMS.ino b/software/firmware/libraries/NeoGPS/examples/NMEAlocDMS/NMEAlocDMS.ino new file mode 100644 index 0000000..cbe1db8 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/examples/NMEAlocDMS/NMEAlocDMS.ino @@ -0,0 +1,117 @@ +#include +#include + +//====================================================================== +// Program: NMEAlocDMS.ino +// +// Description: This program only parses an RMC sentence for the lat/lon. +// +// Prerequisites: +// 1) NMEA.ino works with your device (correct TX/RX pins and baud rate) +// 2) The RMC sentence has been enabled. +// 3) Your device sends an RMC sentence (e.g., $GPRMC). +// +// Serial is for trace output to the Serial Monitor window. +// +// License: +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . +// +//====================================================================== + +#include + +//------------------------------------------------------------ +// Check that the config files are set up properly + +#if !defined( NMEAGPS_PARSE_RMC ) + #error You must uncomment NMEAGPS_PARSE_RMC in NMEAGPS_cfg.h! +#endif + +#if !defined( GPS_FIX_LOCATION_DMS ) + #error You must uncomment GPS_FIX_LOCATION_DMS in GPSfix_cfg.h! +#endif + +#ifdef NMEAGPS_INTERRUPT_PROCESSING + #error You must *NOT* define NMEAGPS_INTERRUPT_PROCESSING in NMEAGPS_cfg.h! +#endif + +//------------------------------------------------------------ + +static NMEAGPS gps; // This parses the GPS characters + +static void doSomeWork( const gps_fix & fix ); +static void doSomeWork( const gps_fix & fix ) +{ + // This is the best place to do your time-consuming work, right after + // the RMC sentence was received. If you do anything in "loop()", + // you could cause GPS characters to be lost, and you will not + // get a good lat/lon. + // For this example, we just print the lat/lon. If you print too much, + // this routine will not get back to "loop()" in time to process + // the next set of GPS data. + + if (fix.valid.location) { + + DEBUG_PORT << fix.latitudeDMS; + DEBUG_PORT.print( fix.latitudeDMS.NS() ); + DEBUG_PORT.write( ' ' ); + if (fix.longitudeDMS.degrees < 100) + DEBUG_PORT.write( '0' ); + DEBUG_PORT << fix.longitudeDMS; + DEBUG_PORT.print( fix.longitudeDMS.EW() ); + + } else { + // No valid location data yet! + DEBUG_PORT.print( '?' ); + } + + DEBUG_PORT.println(); + +} // doSomeWork + +//------------------------------------ + +static void GPSloop(); +static void GPSloop() +{ + while (gps.available( gpsPort )) + doSomeWork( gps.read() ); + +} // GPSloop + +//-------------------------- + +void setup() +{ + DEBUG_PORT.begin(9600); + while (!DEBUG_PORT) + ; + + DEBUG_PORT.print( F("NMEAlocDMS.INO: started\n") ); + DEBUG_PORT.println( F("Looking for GPS device on " GPS_PORT_NAME) ); + DEBUG_PORT.flush(); + + gpsPort.begin(9600); +} + +//-------------------------- + +void loop() +{ + GPSloop(); +} diff --git a/software/firmware/libraries/NeoGPS/examples/NMEAorder/NMEAorder.ino b/software/firmware/libraries/NeoGPS/examples/NMEAorder/NMEAorder.ino new file mode 100644 index 0000000..9389946 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/examples/NMEAorder/NMEAorder.ino @@ -0,0 +1,247 @@ +#include + +//====================================================================== +// Program: NMEAorder.ino +// +// Description: This example program records the order of sentences +// received in each 1-second interval. The last sentence is +// important to know, as that will be used to determine when the +// GPS quiet time is starting (see NMEA.ino). It is safe to perform +// time-consuming operations at that point, and the risk of losing +// characters will be minimized (see comments in 'GPSloop'). +// +// Prerequisites: +// 1) Your GPS device has been correctly powered. +// Be careful when connecting 3.3V devices. +// 2) Your GPS device is correctly connected to an Arduino serial port. +// See GPSport.h for the default connections. +// 3) You know the default baud rate of your GPS device +// Use NMEAdiagnostic.ino to scan for the correct baud rate. +// 4) NMEAGPS_RECOGNIZE_ALL must be enabled in NMEAGPS_cfg.h +// +// 'Serial' is for debug output to the Serial Monitor window. +// +// License: +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . +// +//====================================================================== + +#include + +//------------------------------------------------------------ +// Check configuration + +#ifndef NMEAGPS_RECOGNIZE_ALL + #error You must define NMEAGPS_RECOGNIZE_ALL in NMEAGPS_cfg.h! +#endif + +#ifdef NMEAGPS_INTERRUPT_PROCESSING + #error You must *NOT* define NMEAGPS_INTERRUPT_PROCESSING in NMEAGPS_cfg.h! +#endif + +static NMEAGPS gps ; // This parses received characters +static uint32_t last_rx = 0L; // The last millis() time a character was + // received from GPS. This is used to + // determine when the GPS quiet time begins. + +//------------------------------------------------------------ + +static NMEAGPS::nmea_msg_t last_sentence_in_interval = NMEAGPS::NMEA_UNKNOWN; +static uint8_t prev_sentence_count = 0; +static uint8_t sentence_count = 0; +static const uint8_t MAX_SENTENCES = 20; // per second +static NMEAGPS::nmea_msg_t sentences[ MAX_SENTENCES ]; + +static void recordSentenceTypes() +{ + // Always save the last sentence, even if we're full + sentences[ sentence_count ] = gps.nmeaMessage; + if (sentence_count < MAX_SENTENCES-1) + sentence_count++; + +} // recordSentenceTypes + +//----------------------------------------------------------- + +static void printSentenceOrder() +{ + DEBUG_PORT.println( F("\nSentence order in each 1-second interval:") ); + + for (uint8_t i=0; i 5) { + + // The GPS device has not sent any characters for at least 5ms. + // See if we've been getting chars sometime during the last second. + // If not, the GPS may not be working or connected properly. + + bool getting_chars = (ms_since_last_rx < 1000UL); + static uint32_t last_quiet_time = 0UL; + bool just_went_quiet = + (((int32_t) (last_rx - last_quiet_time)) > 10L); + bool next_quiet_time = + ((current_ms - last_quiet_time) >= 1000UL); + + if ((getting_chars && just_went_quiet) + || + (!getting_chars && next_quiet_time)) { + + last_quiet_time = current_ms; // Remember for next loop + + // If we're not getting good data, make some suggestions. + + bool allDone = false; + + if (!getting_chars) { + + DEBUG_PORT.println( F("\nCheck GPS device and/or connections. No characters received.\n") ); + + allDone = true; + + } else if (sentence_count == 0) { + + DEBUG_PORT.println( F("No valid sentences, but characters are being received.\n" + "Check baud rate or device protocol configuration.\n" ) ); + + allDone = true; + } + + if (allDone) { + DEBUG_PORT.print( F("\nEND.\n") ); + for (;;) + ; // hang! + } + + // No problem, just a real GPS quiet time. + return true; + } + } + + return false; + +} // quietTimeStarted + +//---------------------------------------------------------------- +// Figure out what sentence the GPS device sends +// as the last sentence in each 1-second interval. + +static void watchForLastSentence() +{ + if (quietTimeStarted()) { + + if (prev_sentence_count != sentence_count) { + + // We have NOT received two full intervals of sentences with + // the same number of sentences in each interval. Start + // recording again. + prev_sentence_count = sentence_count; + sentence_count = 0; + + } else if (sentence_count > 0) { + + // Got it! + last_sentence_in_interval = sentences[ sentence_count-1 ]; + } + } + +} // watchForLastSentence + +//-------------------------- + +void setup() +{ + DEBUG_PORT.begin(9600); + while (!DEBUG_PORT) + ; + + DEBUG_PORT.print( F("NMEAorder.INO: started\n") ); + DEBUG_PORT.print( F("fix object size = ") ); + DEBUG_PORT.println( sizeof(gps.fix()) ); + DEBUG_PORT.print( F("NMEAGPS object size = ") ); + DEBUG_PORT.println( sizeof(gps) ); + DEBUG_PORT.println( F("Looking for GPS device on " GPS_PORT_NAME) ); + DEBUG_PORT.flush(); + + gpsPort.begin( 9600 ); +} + +//-------------------------- + +void loop() +{ + GPSloop(); + + if (last_sentence_in_interval == NMEAGPS::NMEA_UNKNOWN) + watchForLastSentence(); + else { + + printSentenceOrder(); + for (;;) + ; // All done! + } +} diff --git a/software/firmware/libraries/NeoGPS/examples/NMEArevGeoCache/NMEArevGeoCache.ino b/software/firmware/libraries/NeoGPS/examples/NMEArevGeoCache/NMEArevGeoCache.ino new file mode 100644 index 0000000..a32dd8c --- /dev/null +++ b/software/firmware/libraries/NeoGPS/examples/NMEArevGeoCache/NMEArevGeoCache.ino @@ -0,0 +1,259 @@ +#include + +//====================================================================== +// Program: NMEArevGeoCache.ino +// +// Description: Activates a servo when the current location is +// close enough to the target location. +// +// Prerequisites: +// 1) NMEA.ino works with your device (correct TX/RX pins and baud rate) +// 2) The RMC sentence has been enabled. +// 3) Your device sends an RMC sentence (e.g., $GPRMC). +// +// Additional Hardware examples: +// 16x2 Character LCD: https://www.adafruit.com/products/181) +// Servo : TPro Micro SG90 https://www.adafruit.com/products/169 +// +// 'Serial' is for debug output to the Serial Monitor window. +// +// Credits: +// This is simplified version of bnordlund9's Geobox: +// http://www.youtube.com/watch?v=g0060tcuofg +// +// Engagement Box by Kenton Harris 11/12/2012 +// +// Reverse Geocache idea by Mikal Hart of http://arduiniana.org/ +// +// License: +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . +// +//====================================================================== + +#include + +//------------------------------------------------------------ +// Check that the config files are set up properly + +#if !defined( NMEAGPS_PARSE_RMC ) & \ + !defined( NMEAGPS_PARSE_GGA ) & \ + !defined( NMEAGPS_PARSE_GLL ) + #error You must uncomment at least one of NMEAGPS_PARSE_RMC, NMEAGPS_PARSE_GGA or NMEAGPS_PARSE_GLL in NMEAGPS_cfg.h! +#endif + +#if !defined( GPS_FIX_LOCATION ) + #error You must uncomment GPS_FIX_LOCATION in GPSfix_cfg.h! +#endif + +//------------------------------------------------------------ +// Additional Hardware includes +#include +//#include + +#include +PWMServo servoLatch; +const int servoLock = 180; // angle (deg) of "locked" servo +const int servoUnlock = 105; // angle (deg) of "unlocked" servo + +using namespace NeoGPS; +NMEAGPS gps; + + float range; // current distance from HERE to THERE +const float CLOSE_ENOUGH = 300.0; // miles, change for your needs + +LiquidCrystal lcd(7, 8, 6, 10, 11, 12); + +const int fixLEDPin = 4; +const int servoPin = 9; + +// The target location, in degrees * 10,000,000 +Location_t there( 384602500, -1098191667L ); + // 38°27'36.2"N 109°49'15.4"W + +void setup() +{ + servoLatch.attach(SERVO_PIN_A); + servoLatch.write(servoLock); + delay(50); + + lcd.begin(16, 2); + + Serial.begin(9600); + Serial.println( F("Debug GPS Test:") ); + + gpsPort.begin(9600); + + // Configure GPS (these are Adafruit GPS commands - your brand may be different) + gpsPort.print + ( F( "$PMTK314,0,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0*29\r\n" // RMC only... + "$PMTK220,1000*1F\r\n" ) ); // ...and 1 Hz update rate + +} // setup + +void loop() +{ + static uint8_t warningState = 0; + static uint32_t lastFixTime, lastDotTime; + + while (gps.available( gpsPort )) { + gps_fix fix = gps.read(); // save the latest + + // Set the "fix" LED to on or off + bool gpsWasFixed = fix.valid.status && (fix.status >= gps_fix::STATUS_STD); + digitalWrite( fixLEDPin, gpsWasFixed ); + + // When we have a location, calculate how far away we are from "there". + if (fix.valid.location) { + lastFixTime = millis(); + + range = fix.location.DistanceMiles( there ); + + //for GPS debug + DEBUG_PORT.print( F("Here: ") ); + //printDMS( DEBUG_PORT, fix.location ); + printAsFloat( DEBUG_PORT, fix.location ); + + DEBUG_PORT.print( F(" There: ") ); + //printDMS( DEBUG_PORT, there ); + printAsFloat( DEBUG_PORT, there ); + + DEBUG_PORT.print( F("Range: ") ); + DEBUG_PORT.print( range ); + DEBUG_PORT.println( F(" Miles") ); + + // Are we there? + if (range < CLOSE_ENOUGH) { + lcd.setCursor(0,1); + lcd.println( F("Box Unlocking...") ); + delay(500); + servoLatch.write(servoUnlock); + + lcd.clear(); + lcd.setCursor(0,1); + lcd.print( F("Happy Birthday") ); + + for (;;); // hang here + } + + // Nope, just give a little feedback... + lcd.clear(); + lcd.setCursor(0,0); + lcd.print( F("Signal Locked") ); + lcd.setCursor(0,1); + lcd.print( range ); + lcd.print( F(" Miles") ); + + warningState = 0; // restart in case we lose the fix later + } + } + + // Display warnings when the GPS hasn't had a fix for a while + + if (millis() - lastFixTime > 2000UL) { + + if (warningState == 0) { + + // First, show the warning message... + lcd.clear(); + lcd.setCursor(0,0); + lcd.print( F("Acquiring Signal") ); + + warningState = 1; + + } else if (warningState < 10) { + + // ...then some dots, two per second... + if (millis() - lastDotTime > 500UL ) { + lastDotTime = millis(); + lcd.setCursor( warningState-1, 1 ); + lcd.print( '.' ); + + warningState++; + } + + } else if (warningState == 10) { + // ... then tell them what to do. + lcd.setCursor(0,1); + lcd.println( F("Take box outside") ); + + // Don't display anything else until location is valid + warningState++; // 11 + } + } +} // loop + +//---------------------------------------------------------------- + +#include "DMS.h" + +void printDMS( Print & outs, const Location_t & loc ) +{ + DMS_t dms; + dms.From( loc.lat() ); + + outs.print( dms.NS() ); + outs << dms; + + dms.From( loc.lon() ); + outs.print( dms.EW() ); + outs << dms; + +} // printDMS + +//---------------------------------------------------------------- + +void printL( Print & outs, int32_t degE7 ) +{ + // Extract and print negative sign + if (degE7 < 0) { + degE7 = -degE7; + outs.print( '-' ); + } + + // Whole degrees + int32_t deg = degE7 / 10000000L; + outs.print( deg ); + outs.print( '.' ); + + // Get fractional degrees + degE7 -= deg*10000000L; + + // Print leading zeroes, if needed + int32_t factor = 1000000L; + while ((degE7 < factor) && (factor > 1L)){ + outs.print( '0' ); + factor /= 10L; + } + + // Print fractional degrees + outs.print( degE7 ); + +} // printL + +//---------------------------------------------------------------- + +void printAsFloat( Print & outs, const Location_t &loc ) +{ + printL( outs, loc.lat() ); // display decimal degrees or... +// printDMS( outs, loc.lat() ); // ... display degrees minutes seconds + + outs.print( F(", ") ); + + printL( outs, loc.lat() ); +// printDMS( outs, loc.lat() ); +} diff --git a/software/firmware/libraries/NeoGPS/examples/NMEAsimple/NMEAsimple.ino b/software/firmware/libraries/NeoGPS/examples/NMEAsimple/NMEAsimple.ino new file mode 100644 index 0000000..1e5bc1d --- /dev/null +++ b/software/firmware/libraries/NeoGPS/examples/NMEAsimple/NMEAsimple.ino @@ -0,0 +1,72 @@ +#include + +//====================================================================== +// Program: NMEAsimple.ino +// +// Description: This program shows simple usage of NeoGPS +// +// Prerequisites: +// 1) NMEA.ino works with your device (correct TX/RX pins and baud rate) +// 2) At least one of the RMC, GGA or GLL sentences have been enabled in NMEAGPS_cfg.h. +// 3) Your device at least one of those sentences (use NMEAorder.ino to confirm). +// 4) LAST_SENTENCE_IN_INTERVAL has been set to one of those sentences in NMEAGPS_cfg.h (use NMEAorder.ino). +// 5) LOCATION and ALTITUDE have been enabled in GPSfix_cfg.h +// +// 'Serial' is for debug output to the Serial Monitor window. +// +// License: +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . +// +//====================================================================== + +#include + +NMEAGPS gps; // This parses the GPS characters +gps_fix fix; // This holds on to the latest values + +void setup() +{ + DEBUG_PORT.begin(9600); + while (!Serial) + ; + DEBUG_PORT.print( F("NMEAsimple.INO: started\n") ); + + gpsPort.begin(9600); +} + +//-------------------------- + +void loop() +{ + while (gps.available( gpsPort )) { + fix = gps.read(); + + DEBUG_PORT.print( F("Location: ") ); + if (fix.valid.location) { + DEBUG_PORT.print( fix.latitude(), 6 ); + DEBUG_PORT.print( ',' ); + DEBUG_PORT.print( fix.longitude(), 6 ); + } + + DEBUG_PORT.print( F(", Altitude: ") ); + if (fix.valid.altitude) + DEBUG_PORT.print( fix.altitude() ); + + DEBUG_PORT.println(); + } +} diff --git a/software/firmware/libraries/NeoGPS/examples/NMEAtest/NMEAtest.ino b/software/firmware/libraries/NeoGPS/examples/NMEAtest/NMEAtest.ino new file mode 100644 index 0000000..efd56a6 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/examples/NMEAtest/NMEAtest.ino @@ -0,0 +1,771 @@ +#include +using namespace NeoGPS; + +//====================================================================== +// Program: NMEAtest.ino +// +// Prerequisites: +// 1) All NMEA standard messages and Satellite Information +// are enabled. +// 2) All 'gps_fix' members are enabled. +// 3) All validation options are enabled. +// +// Description: This test program uses one GPGGA sentence +// to test the parser's: +// 1) robustness WRT dropped, inserted, and mangled characters +// 2) correctness WRT values extracted from the input stream +// +// Some care in testing must be taken because +// 1) The XOR-style checksum is not very good at catching errors. +// 2) The '*' is a special character for delimiting the CRC. If +// it is changed, a CR/LF will allow the sentence to pass. +// +// 'Serial' is for debug output to the Serial Monitor window. +// +// License: +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . +// +//====================================================================== + +#include + +//------------------------------------------------------------ +// Check that the config files are set up properly + +#if !defined(NMEAGPS_PARSE_GGA) | \ + !defined(NMEAGPS_PARSE_GLL) | \ + !defined(NMEAGPS_PARSE_GSA) | \ + !defined(NMEAGPS_PARSE_GST) | \ + !defined(NMEAGPS_PARSE_GSV) | \ + !defined(NMEAGPS_PARSE_RMC) | \ + !defined(NMEAGPS_PARSE_VTG) | \ + !defined(NMEAGPS_PARSE_ZDA) + + #error NMEAGPS_PARSE_GGA, GLL, GSA, GSV, RMC, VTG and ZDA must be defined in NMEAGPS_cfg.h! +#endif + +#ifndef GPS_FIX_DATE + #error GPS_FIX_DATE must be defined in GPSfix_cfg.h! +#endif + +#ifndef GPS_FIX_TIME + #error GPS_FIX_TIME must be defined in GPSfix_cfg.h! +#endif + +#ifndef GPS_FIX_LOCATION + #error GPS_FIX_LOCATION must be defined in GPSfix_cfg.h! +#endif + +#ifndef GPS_FIX_LOCATION_DMS + #error GPS_FIX_LOCATION_DMS must be defined in GPSfix_cfg.h! +#endif + +#ifndef GPS_FIX_ALTITUDE + #error GPS_FIX_ALTITUDE must be defined in GPSfix_cfg.h! +#endif + +#ifndef GPS_FIX_SPEED + #error GPS_FIX_SPEED must be defined in GPSfix_cfg.h! +#endif + +#ifndef GPS_FIX_HEADING + #error GPS_FIX_HEADING must be defined in GPSfix_cfg.h! +#endif + +#ifndef GPS_FIX_SATELLITES + #error GPS_FIX_SATELLITES must be defined in GPSfix_cfg.h! +#endif + +#ifndef GPS_FIX_HDOP + #error GPS_FIX_HDOP must be defined in GPSfix_cfg.h! +#endif + +#ifndef GPS_FIX_GEOID_HEIGHT + #error GPS_FIX_GEOID_HEIGHT must be defined in GPSfix_cfg.h! +#endif + +static NMEAGPS gps; + +//-------------------------- +// Example sentences + +struct LocVector_t + { + float range; + float bearing; + }; + +static Location_t AyersRock( -253448688L, 1310324914L ); +// -25.3448688,131.0324914 +// 2520.692128,S,13101.949484,E +// 25 20' 41.528" S 131 1' 56.969" E +static const LocVector_t NiihauToAyersRock = { 9078.681, 238.33972 }; + +const char validRMC[] __PROGMEM = + "$GPRMC,092725.00,A,2520.69213,S,13101.94948,E," + "0.004,77.52,091202,,,A*43\r\n"; + +//........................... + +static Location_t ubloxHQ( 472852369L, 85630763L ); // near Zurich, Switzerland +// 47.2852369, 8.5630763 +// 47 17' 6.840" N 008 33' 54.954" E +static const LocVector_t NiihauToUblox = { 12248.67, 8.0625 }; + +const char validGGA[] __PROGMEM = + "$GPGGA,092725.00,4717.113993,N,00833.915904,E," + "1,8,1.01,499.6,M,48.0,M,,0*5C\r\n"; + +//........................... + +static Location_t MacchuPicchu( -131628050L, -725455080L ); +// -13.162805, -72.545508 +// 13.162805,S,72.545508,W +// 13 09' 46.098" S 72 32' 43.830" W +static const LocVector_t NiihauToMacchu = { 10315.93, 103.07306 }; + +const char validGGA2[] __PROGMEM = + "$GPGGA,162254.00,1309.7683,S,7232.7305,W,1,03,2.36,2430.2,M,-25.6,M,,*7E\r\n"; + +//........................... + +static Location_t DexterMO( 367944050L, -899586550L ); +// 36.794405, -89.958655 +// 36.794405,N,89.958655,W +// 36 47' 39.858" N 89 57' 31.158" W +static const LocVector_t NiihauToDexter = { 6865.319, 58.85472 }; + +const char validRMC2[] __PROGMEM = + "$GPRMC,162254.00,A,3647.6643,N,8957.5193,W,0.820,188.36,110706,,,A*49\r\n"; + +//........................... + +static Location_t NiihauHI( 218276210L, -1602448760L ); +// 21.827621, -160.244876 +// 21.827621,N,160.244876,W +// 21 49' 39.4356" N 160 14' 41.5536 W +static const LocVector_t NiihauToNiihau = { 0.0, 90.0 }; + +const char validRMC3[] __PROGMEM = +"$GPRMC,235959.99,A,2149.65726,N,16014.69256,W,8.690,359.99,051015,9.47,E,A*26\r\n"; + +// 218276212L, -1602448757L +// 21 49.65727' N 160 14.69254' W +// 21 49' 39.4362" N 160 14' 41.5524" W +const char validRMC4[] __PROGMEM = +"$GPRMC,235959.99,A,2149.65727,N,16014.69254,W,8.690,359.99,051015,9.47,E,A*25\r\n"; +static const LocVector_t NiihauToNiihau2 = { 0.00003812513, 54.31585 }; + +//........................... + +static Location_t JujaKenya( -10934552L, 370261835L ); + +// -1.0934552, 37.0261835 +// 01 05' 36.458" S 037 01' 42.140" E +static const LocVector_t NiihauToJuja = { 17046.24, 318.6483 }; + +const char validGLL[] __PROGMEM = +"$GNGLL,0105.60764,S,03701.70233,E,225627.00,A,A*6B\r\n"; + +//-------------------------------- + +const char mtk1[] __PROGMEM = +"$GPGGA,064951.000,2307.1256,N,12016.4438,E,1,8,0.95,39.9,M,17.8,M,,*63\r\n"; +const char mtk2[] __PROGMEM = +"$GPRMC,064951.000,A,2307.1256,N,12016.4438,E,0.03,165.48,260406,3.05,W,A*2C\r\n"; +const char mtk3[] __PROGMEM = +"$GPVTG,165.48,T,,M,0.03,N,0.06,K,A*36\r\n"; +const char mtk4[] __PROGMEM = +"$GPGSA,A,3,29,21,26,15,18,09,06,10,,,,,2.32,0.95,2.11*00\r\n"; +const char mtk5[] __PROGMEM = +"$GPGSV,3,1,09,29,36,029,42,21,46,314,43,26,44,020,43,15,21,321,39*7D\r\n"; +const char mtk6[] __PROGMEM = +"$GPGSV,3,2,09,18,26,314,40,09,57,170,44,06,20,229,37,10,26,084,37*77\r\n"; +const char mtk7[] __PROGMEM = +"$GPGSV,3,3,09,07,,,26*73\r\n"; +const char mtk7a[] __PROGMEM = +"$GLGSV,1,1,4,29,36,029,42,21,46,314,43,26,44,020,43,15,21,321,39*5E\r\n"; +const char mtk8[] __PROGMEM = +"$GNGST,082356.00,1.8,,,,1.7,1.3,2.2*60\r\n"; +const char mtk9[] __PROGMEM = +"$GNRMC,083559.00,A,4717.11437,N,00833.91522,E,0.004,77.52,091202,,,A,V*33\r\n"; +const char mtk10[] __PROGMEM = +"$GNGGA,092725.00,4717.11399,N,00833.91590,E,1,08,1.01,499.6,M,48.0,M,,*45\r\n"; +const char mtk11[] __PROGMEM = + "$GLZDA,225627.00,21,09,2015,00,00*70\r\n"; + +const char fpGGA00[] __PROGMEM = "$GPGGA,092725.00,3242.9000,N,11705.816900,W," + "1,8,1.01,499.6,M,48.0,M,,0*49\r\n"; +const char fpGGA01[] __PROGMEM = "$GPGGA,092725.00,3242.9000,N,11705.816901,W," + "1,8,1.01,499.6,M,48.0,M,,0*48\r\n"; +const char fpGGA02[] __PROGMEM = "$GPGGA,092725.00,3242.9000,N,11705.816902,W," + "1,8,1.01,499.6,M,48.0,M,,0*4B\r\n"; +const char fpGGA03[] __PROGMEM = "$GPGGA,092725.00,3242.9000,N,11705.816903,W," + "1,8,1.01,499.6,M,48.0,M,,0*4A\r\n"; +const char fpGGA04[] __PROGMEM = "$GPGGA,092725.00,3242.9000,N,11705.816904,W," + "1,8,1.01,499.6,M,48.0,M,,0*4D\r\n"; +const char fpGGA05[] __PROGMEM = "$GPGGA,092725.00,3242.9000,N,11705.816905,W," + "1,8,1.01,499.6,M,48.0,M,,0*4C\r\n"; +const char fpGGA06[] __PROGMEM = "$GPGGA,092725.00,3242.9000,N,11705.816906,W," + "1,8,1.01,499.6,M,48.0,M,,0*4F\r\n"; +const char fpGGA07[] __PROGMEM = "$GPGGA,092725.00,3242.9000,N,11705.816907,W," + "1,8,1.01,499.6,M,48.0,M,,0*4E\r\n"; +const char fpGGA08[] __PROGMEM = "$GPGGA,092725.00,3242.9000,N,11705.816908,W," + "1,8,1.01,499.6,M,48.0,M,,0*41\r\n"; +const char fpGGA09[] __PROGMEM = "$GPGGA,092725.00,3242.9000,N,11705.816909,W," + "1,8,1.01,499.6,M,48.0,M,,0*40\r\n"; +const char fpGGA10[] __PROGMEM = "$GPGGA,092725.00,3242.9000,N,11705.816910,W," + "1,8,1.01,499.6,M,48.0,M,,0*48\r\n"; + +//-------------------------- + +static bool parse_P( const char *ptr ) +{ + bool decoded = false; + char c; + + gps.fix().init(); + while ( (c = pgm_read_byte( ptr++ )) != '\0' ) { + if (NMEAGPS::DECODE_COMPLETED == gps.decode( c )) { + decoded = true; + } + } + + return decoded; +} + +//-------------------------- + +static void traceSample( const char *ptr, bool init = true ) +{ + Serial << F("Input: ") << (const __FlashStringHelper *) ptr; + + if (init) + gps.data_init(); + bool decoded = parse_P( ptr ); + + if (decoded) + Serial << F("Results: "); + else + Serial << F("Failed to decode! "); + + trace_all( Serial, gps, gps.fix() ); + Serial << '\n'; +} + +//-------------------------- + +static uint8_t passed = 0; +static uint8_t failed = 0; + +static void checkFix + ( const char *msg, NMEAGPS::nmea_msg_t msg_type, gps_fix::status_t status, + int32_t lat, int32_t lon, + uint8_t latDeg, uint8_t latMin, uint8_t latSec, uint16_t latSecFrac, Hemisphere_t ns, + uint8_t lonDeg, uint8_t lonMin, uint8_t lonSec, uint16_t lonSecFrac, Hemisphere_t ew, + const LocVector_t & to ) +{ + const char *ptr = msg; + for (;;) { + char c = pgm_read_byte( ptr++ ); + if (!c) { + Serial.print( F("FAILED to parse \"") ); + Serial.print( (const __FlashStringHelper *) msg ); + Serial.println( F("\"\n") ); + failed++; + break; + } + if (NMEAGPS::DECODE_COMPLETED == gps.decode( c )) { + bool ok = true; + const gps_fix & fix = gps.fix(); + + if (gps.nmeaMessage != msg_type) { + Serial.print( F("FAILED wrong message type ") ); + Serial.println( gps.nmeaMessage ); + failed++; + ok = false; + } + if (fix.status != status ) { + Serial.print( F("FAILED wrong status ") ); + Serial.print( fix.status ); + Serial.print( F(" (expected ") ); + Serial.print( status ); + Serial.println( ')' ); + failed++; + ok = false; + } + if (fix.latitudeL() != lat) { + Serial.print( F("FAILED wrong latitude ") ); + Serial.print( fix.latitudeL() ); + Serial.print( F(" (expected ") ); + Serial.print( lat ); + Serial.println( ')' ); + failed++; + ok = false; + } + if (fix.longitudeL() != lon) { + Serial.print( F("FAILED wrong longitude ") ); + Serial.print( fix.longitudeL() ); + Serial.print( F(" (expected ") ); + Serial.print( lon ); + Serial.println( ')' ); + failed++; + ok = false; + } + + if (fix.latitudeDMS.degrees != latDeg) { + Serial.print( F("FAILED wrong latitude degrees ") ); + Serial.print( fix.latitudeDMS.degrees ); + Serial.print( F(", expected ") ); + Serial.println( latDeg ); + failed++; + ok = false; + } + if (fix.latitudeDMS.minutes != latMin) { + Serial.print( F("FAILED wrong latitude minutes ") ); + Serial.print( fix.latitudeDMS.minutes ); + Serial.print( F(", expected ") ); + Serial.println( latMin ); + failed++; + ok = false; + } + if (fix.latitudeDMS.seconds_whole != latSec) { + Serial.print( F("FAILED wrong latitude seconds ") ); + Serial.print( fix.latitudeDMS.seconds_whole ); + Serial.print( F(", expected ") ); + Serial.println( latSec ); + failed++; + ok = false; + } + int8_t fracDiff = (int8_t)(fix.latitudeDMS.seconds_frac - latSecFrac); + const int8_t ieps = 1; + if (abs(fracDiff) > ieps) { + Serial.print( F("FAILED wrong latitude seconds fraction ") ); + Serial.print( fix.latitudeDMS.seconds_frac ); + Serial.print( F(", expected ") ); + Serial.println( latSecFrac ); + failed++; + ok = false; + } + if (fix.latitudeDMS.hemisphere != ns) { + Serial.print( F("FAILED wrong latitude NS ") ); + Serial.println( fix.latitudeDMS.NS() ); + failed++; + ok = false; + } + + if (fix.longitudeDMS.degrees != lonDeg) { + Serial.print( F("FAILED wrong longitude degrees ") ); + Serial.print( fix.longitudeDMS.degrees ); + Serial.print( F(", expected ") ); + Serial.println( lonDeg ); + failed++; + ok = false; + } + if (fix.longitudeDMS.minutes != lonMin) { + Serial.print( F("FAILED wrong longitude minutes ") ); + Serial.print( fix.longitudeDMS.minutes ); + Serial.print( F(", expected ") ); + Serial.println( lonMin ); + failed++; + ok = false; + } + if (fix.longitudeDMS.seconds_whole != lonSec) { + Serial.print( F("FAILED wrong longitude seconds ") ); + Serial.print( fix.longitudeDMS.seconds_whole ); + Serial.print( F(", expected ") ); + Serial.println( lonSec ); + failed++; + ok = false; + } + fracDiff = (int8_t)(fix.longitudeDMS.seconds_frac - lonSecFrac); + if (abs(fracDiff) > ieps) { + Serial.print( F("FAILED wrong longitude seconds fraction ") ); + Serial.print( fix.longitudeDMS.seconds_frac ); + Serial.print( F(", expected ") ); + Serial.println( lonSecFrac ); + failed++; + ok = false; + } + if (fix.longitudeDMS.hemisphere != ew) { + Serial.print( F("FAILED wrong longitude EW ") ); + Serial.println( fix.longitudeDMS.EW() ); + failed++; + ok = false; + } + + char floatChars[16]; + float distance = NiihauHI.DistanceKm( fix.location ); + float diff = abs( distance - to.range ); + if ( (diff/to.range) > 0.000001 ) { + Serial.print( F("FAILED distance ") ); + dtostre( distance, floatChars, 6, DTOSTR_PLUS_SIGN ); + Serial.print( floatChars ); + Serial.print( F(" != ") ); + dtostre( to.range, floatChars, 6, DTOSTR_PLUS_SIGN ); + Serial.println( floatChars ); + failed++; + ok = false; + } + + float courseTo = NiihauHI.BearingToDegrees( fix.location ); + diff = abs( courseTo - to.bearing ); + if ( diff > 0.005 ) { + Serial.print( F("FAILED bearing ") ); + dtostre( courseTo, floatChars, 6, DTOSTR_PLUS_SIGN ); + Serial.print( floatChars ); + Serial.print( F(" != ") ); + dtostre( to.bearing, floatChars, 6, DTOSTR_PLUS_SIGN ); + Serial.print( floatChars ); + failed++; + ok = false; + } + + if (ok) + passed++; + break; + } + } +} + +//-------------------------- + +void setup() +{ + // Start the normal trace output + Serial.begin(9600); + + Serial.print( F("NMEA test: started\n") ); + Serial.print( F("fix object size = ") ); + Serial.println( sizeof(gps_fix) ); + Serial.print( F("gps object size = ") ); + Serial.println( sizeof(NMEAGPS) ); + + // Some basic rejection tests + Serial.println( F("Test rejection of all byte values") ); + for (uint16_t c=0; c < 256; c++) { + if (c != '$') { + if (NMEAGPS::DECODE_CHR_INVALID != gps.decode( (char)c )) { + Serial.print( F("FAILED to reject single character ") ); + Serial.println( c ); + failed++; + return; + } + } + } + passed++; + + Serial.println( F("Test rejection of multiple $") ); + for (uint16_t i=0; i < 256; i++) { + if (NMEAGPS::DECODE_COMPLETED == gps.decode( '$' )) { + Serial.print( F("FAILED to reject multiple '$' characters\n") ); + failed++; + return; + } + } + passed++; + + uint16_t validGGA_len = 0; + + // Insert a ' ' at each position of the test sentence + Serial.println( F("Insert ' '") ); + uint16_t insert_at = 1; + do { + const char *ptr = validGGA; + uint8_t j = 0; + for (;;) { + if (j++ == insert_at) { + NMEAGPS::decode_t result = gps.decode( ' ' ); + if (gps.validateChars() || gps.validateFields()) { + if (result == NMEAGPS::DECODE_COMPLETED) { + Serial.print( F("FAILED incorrectly decoded ' ' @ pos ") ); + Serial.println( insert_at ); + failed++; + } else if (gps.nmeaMessage != NMEAGPS::NMEA_UNKNOWN) { + Serial.print( F("FAILED incorrectly accepted ' ' @ pos ") ); + Serial.println( insert_at ); + failed++; + } + } + } + char c = pgm_read_byte( ptr++ ); + if (!c) { + if (validGGA_len == 0) { + validGGA_len = j-1; + Serial.print( F("Test string length = ") ); + Serial.println( validGGA_len ); + } + break; + } + if (gps.decode( c ) == NMEAGPS::DECODE_COMPLETED) { + Serial.print( F("FAILED incorrectly decoded @ pos ") ); + Serial.println( insert_at ); + failed++; + //return; + } + } + } while (++insert_at < validGGA_len-2); + passed++; + + // Drop one character from each position in example sentence + Serial.println( F("Drop character") ); + for (uint16_t i=0; i < validGGA_len-3; i++) { + const char *ptr = validGGA; + uint8_t firstInvalidPos = 0; + char dropped = 0; + for (uint8_t j = 0;; j++) { + char c = pgm_read_byte( ptr++ ); + if (!c || (c == '*')) break; + + if (j == i) { + dropped = c; + } else { + NMEAGPS::decode_t result = gps.decode( c ); + if (result == NMEAGPS::DECODE_COMPLETED) { + Serial.print( F("FAILED decoded after dropping '") ); + Serial << dropped; + Serial.print( F("' at pos ") ); + Serial.println( i ); + failed++; + } else if (gps.nmeaMessage == NMEAGPS::NMEA_UNKNOWN) { + if (firstInvalidPos != 0) + firstInvalidPos = j; + } + } + } + if (firstInvalidPos != 0) { + Serial.print( F(" /*") ); + Serial.print( i ); + Serial.print( F("*/ ") ); + Serial.println( firstInvalidPos ); + } + } + passed++; + + // Mangle one character from each position in example sentence + Serial.println( F("Mangle one character") ); + for (uint16_t i=0; i < validGGA_len-3; i++) { + const char *ptr = validGGA; + uint8_t j = 0; + char replaced = 0; + for (;;) { + char c = pgm_read_byte( ptr++ ); + if (!c || (c == '*')) break; + if (j++ == i) + replaced = c++; // mangle means increment + if (NMEAGPS::DECODE_COMPLETED == gps.decode( c )) { + Serial.print( F("FAILED replacing '") ); + Serial << (uint8_t) replaced; + Serial.print( F("' with '") ); + Serial << (uint8_t) (replaced+1); + Serial.print( F("' at pos ") ); + Serial.println( i ); + failed++; + break; + //return; + } + } + } + passed++; + + // Verify that exact values are extracted + Serial.println( F("Verify parsed values") ); + { + const char *ptr = validGGA; + for (;;) { + char c = pgm_read_byte( ptr++ ); + if (!c) { + Serial.print( F("FAILED to parse \"") ); + Serial.print( (str_P) validGGA ); + Serial.println( F("\"\n") ); + failed++; + break; + } + if (NMEAGPS::DECODE_COMPLETED == gps.decode( c )) { + gps_fix expected; + expected.dateTime.parse( PSTR("2002-12-09 09:27:25") ); + expected.dateTime_cs = 0; + + if (gps.nmeaMessage != NMEAGPS::NMEA_GGA) { + Serial.print( F("FAILED wrong message type ") ); + Serial.println( gps.nmeaMessage ); + failed++; + break; + } + if ((gps.fix().dateTime.hours != expected.dateTime.hours ) || + (gps.fix().dateTime.minutes != expected.dateTime.minutes) || + (gps.fix().dateTime.seconds != expected.dateTime.seconds) || + (gps.fix().dateTime_cs != expected.dateTime_cs)) { + Serial << F("FAILED wrong time ") << gps.fix().dateTime << '.' << gps.fix().dateTime_cs << F(" != ") << expected.dateTime << '.' << expected.dateTime_cs << '\n'; + failed++; + break; + } + if (gps.fix().latitudeL() != 472852332L) { + Serial.print( F("FAILED wrong latitude ") ); + Serial.println( gps.fix().latitudeL() ); + failed++; + break; + } + if (gps.fix().longitudeL() != 85652651L) { + Serial.print( F("FAILED wrong longitude ") ); + Serial.println( gps.fix().longitudeL() ); + failed++; + break; + } + if (gps.fix().status != gps_fix::STATUS_STD) { + Serial.print( F("FAILED wrong status ") ); + Serial.println( gps.fix().status ); + failed++; + break; + } + if (gps.fix().satellites != 8) { + Serial.print( F("FAILED wrong satellites ") ); + Serial.println( gps.fix().satellites ); + failed++; + break; + } + if (gps.fix().hdop != 1010) { + Serial.print( F("FAILED wrong HDOP ") ); + Serial.println( gps.fix().hdop ); + failed++; + break; + } + if (gps.fix().altitude_cm() != 49960) { + Serial.print( F("FAILED wrong altitude ") ); + Serial.println( gps.fix().longitudeL() ); + failed++; + break; + } + break; + } + } + } + passed++; + + checkFix( validRMC , NMEAGPS::NMEA_RMC, gps_fix::STATUS_STD, + -253448688L, 1310324913L, + 25, 20, 41, 528, SOUTH_H, 131, 1, 56, 969, EAST_H, + NiihauToAyersRock ); + checkFix( validGGA , NMEAGPS::NMEA_GGA, gps_fix::STATUS_STD, + 472852332L, 85652651L, + 47, 17, 6, 840, NORTH_H, 8, 33, 54, 954, EAST_H, + NiihauToUblox ); + if (gps.fix().geoidHeight_cm() != 4800) { + Serial.print( F("FAILED wrong geoid height for 48.00") ); + Serial.println( gps.fix().geoidHeight_cm() ); + failed++; + } + checkFix( validGGA2, NMEAGPS::NMEA_GGA, gps_fix::STATUS_STD, + -131628050L, -725455083L, + 13, 9, 46, 98, SOUTH_H, 72, 32, 43, 830, WEST_H, + NiihauToMacchu ); + if (gps.fix().geoidHeight_cm() != -2560) { + Serial.print( F("FAILED wrong geoid height for -25.60") ); + Serial.println( gps.fix().geoidHeight_cm() ); + failed++; + } + checkFix( validRMC2, NMEAGPS::NMEA_RMC, gps_fix::STATUS_STD, + 367944050L, -899586550L, + 36, 47, 39, 858, NORTH_H, 89, 57, 31, 158, WEST_H, + NiihauToDexter ); + checkFix( validRMC3, NMEAGPS::NMEA_RMC, gps_fix::STATUS_STD, + 218276210L, -1602448760L, + 21, 49, 39, 436, NORTH_H, 160, 14, 41, 554, WEST_H, + NiihauToNiihau ); + checkFix( validRMC4, NMEAGPS::NMEA_RMC, gps_fix::STATUS_STD, + 218276212L, -1602448757L, + 21, 49, 39, 436, NORTH_H, 160, 14, 41, 552, WEST_H, + NiihauToNiihau2 ); + checkFix( validGLL , NMEAGPS::NMEA_GLL, gps_fix::STATUS_STD, + -10934607L, 370283722L, + 1, 5, 36, 458, SOUTH_H, 37, 1, 42, 140, EAST_H, + NiihauToJuja ); +} + +//-------------------------- + +void loop() +{ + Serial.print( F("PASSED ") ); + Serial << passed; + Serial.println( F(" tests.") ); + + if (failed) { + Serial.print( F("FAILED ") ); + Serial << failed; + Serial.println( F(" tests.") ); + } else { + Serial << F("------ Samples ------\nResults format:\n "); + trace_header( Serial ); + Serial << '\n'; + +#ifdef NMEAGPS_STATS + gps.statistics.init(); +#endif + + traceSample( validGGA ); + traceSample( validGGA2 ); + traceSample( validRMC ); + traceSample( validRMC2 ); + traceSample( validRMC3 ); + traceSample( validGLL ); + traceSample( mtk1 ); + traceSample( mtk2 ); + traceSample( mtk3 ); + traceSample( mtk4 ); + traceSample( mtk5 ); + traceSample( mtk6, false ); + traceSample( mtk7, false ); + traceSample( mtk7a, false ); + traceSample( mtk8 ); + traceSample( mtk9 ); + traceSample( mtk10 ); + traceSample( mtk11 ); + if (!gps.fix().valid.date || + (gps.fix().dateTime.date != 21) || + (gps.fix().dateTime.month != 9) || + (gps.fix().dateTime.year != 15) || + !gps.fix().valid.time || + (gps.fix().dateTime.hours != 22) || + (gps.fix().dateTime.minutes != 56) || + (gps.fix().dateTime.seconds != 27)) + Serial << F("******** ZDA not parsed correctly **********\n"); + + /** + * This next section displays incremental longitudes. + * If you have defined USE_FLOAT in Streamers.cpp, this will show + * how the conversion to /float/ causes loss of accuracy compared + * to the /uint32_t/ values. + */ + Serial << F("--- floating point conversion tests ---\n\n"); + + traceSample( fpGGA00 ); + traceSample( fpGGA01 ); + traceSample( fpGGA02 ); + traceSample( fpGGA03 ); + traceSample( fpGGA04 ); + traceSample( fpGGA05 ); + traceSample( fpGGA06 ); + traceSample( fpGGA07 ); + traceSample( fpGGA08 ); + traceSample( fpGGA09 ); + traceSample( fpGGA10 ); + } + + for (;;); +} diff --git a/software/firmware/libraries/NeoGPS/examples/NMEAtimezone/NMEAtimezone.ino b/software/firmware/libraries/NeoGPS/examples/NMEAtimezone/NMEAtimezone.ino new file mode 100644 index 0000000..8e8abd3 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/examples/NMEAtimezone/NMEAtimezone.ino @@ -0,0 +1,188 @@ +#include + +//====================================================================== +// Program: NMEAtimezone.ino +// +// Description: This program shows how to offset the GPS dateTime member +// into your specific timezone. GPS devices do not know which +// timezone they are in, so they always report a UTC time. This +// is the same as GMT. +// +// Prerequisites: +// 1) NMEA.ino works with your device +// 2) GPS_FIX_TIME is enabled in GPSfix_cfg.h +// 3) NMEAGPS_PARSE_RMC is enabled in NMEAGPS_cfg.h. You could use +// any sentence that contains a time field. Be sure to change the +// "if" statement in GPSloop from RMC to your selected sentence. +// +// 'Serial' is for debug output to the Serial Monitor window. +// +// License: +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . +// +//====================================================================== + +static NMEAGPS gps; // This parses received characters +static gps_fix fix; // This contains all the parsed pieces + +//-------------------------- +// CHECK CONFIGURATION + +#if !defined(GPS_FIX_TIME) | !defined(GPS_FIX_DATE) + #error You must define GPS_FIX_TIME and DATE in GPSfix_cfg.h! +#endif + +#if !defined(NMEAGPS_PARSE_RMC) & !defined(NMEAGPS_PARSE_ZDA) + #error You must define NMEAGPS_PARSE_RMC or ZDA in NMEAGPS_cfg.h! +#endif + +#include + +//-------------------------- +// Set these values to the offset of your timezone from GMT + +static const int32_t zone_hours = -5L; // EST +static const int32_t zone_minutes = 0L; // usually zero +static const NeoGPS::clock_t zone_offset = + zone_hours * NeoGPS::SECONDS_PER_HOUR + + zone_minutes * NeoGPS::SECONDS_PER_MINUTE; + +// Uncomment one DST changeover rule, or define your own: +#define USA_DST +//#define EU_DST + +#if defined(USA_DST) + static const uint8_t springMonth = 3; + static const uint8_t springDate = 14; // latest 2nd Sunday + static const uint8_t springHour = 2; + static const uint8_t fallMonth = 11; + static const uint8_t fallDate = 7; // latest 1st Sunday + static const uint8_t fallHour = 2; + #define CALCULATE_DST + +#elif defined(EU_DST) + static const uint8_t springMonth = 3; + static const uint8_t springDate = 31; // latest last Sunday + static const uint8_t springHour = 1; + static const uint8_t fallMonth = 10; + static const uint8_t fallDate = 31; // latest last Sunday + static const uint8_t fallHour = 1; + #define CALCULATE_DST +#endif + +//-------------------------- + +void adjustTime( NeoGPS::time_t & dt ) +{ + NeoGPS::clock_t seconds = dt; // convert date/time structure to seconds + + #ifdef CALCULATE_DST + // Calculate DST changeover times once per reset and year! + static NeoGPS::time_t changeover; + static NeoGPS::clock_t springForward, fallBack; + + if ((springForward == 0) || (changeover.year != dt.year)) { + + // Calculate the spring changeover time (seconds) + changeover.year = dt.year; + changeover.month = springMonth; + changeover.date = springDate; + changeover.hours = springHour; + changeover.minutes = 0; + changeover.seconds = 0; + changeover.set_day(); + // Step back to a Sunday, if day != SUNDAY + changeover.date -= (changeover.day - NeoGPS::time_t::SUNDAY); + springForward = (NeoGPS::clock_t) changeover; + + // Calculate the fall changeover time (seconds) + changeover.month = fallMonth; + changeover.date = fallDate; + changeover.hours = fallHour - 1; // to account for the "apparent" DST +1 + changeover.set_day(); + // Step back to a Sunday, if day != SUNDAY + changeover.date -= (changeover.day - NeoGPS::time_t::SUNDAY); + fallBack = (NeoGPS::clock_t) changeover; + } + #endif + + // First, offset from UTC to the local timezone + seconds += zone_offset; + + #ifdef CALCULATE_DST + // Then add an hour if DST is in effect + if ((springForward <= seconds) && (seconds < fallBack)) + seconds += NeoGPS::SECONDS_PER_HOUR; + #endif + + dt = seconds; // convert seconds back to a date/time structure + +} // adjustTime + +//-------------------------- + +static void GPSloop() +{ + while (gps.available( gpsPort )) { + fix = gps.read(); + // Display the local time + + if (fix.valid.time && fix.valid.date) { + adjustTime( fix.dateTime ); + + DEBUG_PORT << fix.dateTime; + } + DEBUG_PORT.println(); + } + +} // GPSloop + +//-------------------------- + +#ifdef NMEAGPS_INTERRUPT_PROCESSING + static void GPSisr( uint8_t c ) + { + gps.handle( c ); + } +#endif + +//-------------------------- + +void setup() +{ + DEBUG_PORT.begin(9600); + while (!DEBUG_PORT) + ; + + DEBUG_PORT.print( F("NMEAtimezone.INO: started\n") ); + DEBUG_PORT.println( F("Looking for GPS device on " GPS_PORT_NAME ) ); + DEBUG_PORT.println( F("Local time") ); + DEBUG_PORT.flush(); + + gpsPort.begin( 9600 ); + #ifdef NMEAGPS_INTERRUPT_PROCESSING + gpsPort.attachInterrupt( GPSisr ); + #endif +} + +//-------------------------- + +void loop() +{ + GPSloop(); +} diff --git a/software/firmware/libraries/NeoGPS/examples/PUBX/PUBX.ino b/software/firmware/libraries/NeoGPS/examples/PUBX/PUBX.ino new file mode 100644 index 0000000..a10d4df --- /dev/null +++ b/software/firmware/libraries/NeoGPS/examples/PUBX/PUBX.ino @@ -0,0 +1,156 @@ +#include +#include + +//====================================================================== +// Program: PUBX.ino +// +// Description: This program parses NMEA proprietary messages from +// ublox devices. It is an extension of NMEA.ino. +// +// Prerequisites: +// 1) You have a ublox GPS device +// 2) NMEA.ino works with your device +// 3) You have installed ubxNMEA.H and ubxNMEA.CPP +// 4) At least one NMEA standard or proprietary sentence has been enabled. +// 5) Implicit Merging is disabled. +// +// Serial is for debug output to the Serial Monitor window. +// +// License: +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . +// +//====================================================================== + +#include + +#include + +//------------------------------------------------------------ +// Check that the config files are set up properly + +#if !defined( NMEAGPS_PARSE_GGA ) & !defined( NMEAGPS_PARSE_GLL ) & \ + !defined( NMEAGPS_PARSE_GSA ) & !defined( NMEAGPS_PARSE_GSV ) & \ + !defined( NMEAGPS_PARSE_RMC ) & !defined( NMEAGPS_PARSE_VTG ) & \ + !defined( NMEAGPS_PARSE_ZDA ) & !defined( NMEAGPS_PARSE_GST ) & \ + !defined( NMEAGPS_PARSE_PUBX_00 ) & !defined( NMEAGPS_PARSE_PUBX_04 ) + + #error No NMEA sentences enabled: no fix data available for fusing. + +#endif + +#if !defined( NMEAGPS_PARSE_PUBX_00 ) & !defined( NMEAGPS_PARSE_PUBX_04 ) + #error No PUBX messages enabled! You must enable one or more in ubxNMEA.h! +#endif + +#ifndef NMEAGPS_DERIVED_TYPES + #error You must "#define NMEAGPS_DERIVED_TYPES" in NMEAGPS_cfg.h! +#endif + +#ifndef NMEAGPS_EXPLICIT_MERGING + #error You must define NMEAGPS_EXPLICIT_MERGING in NMEAGPS_cfg.h +#endif + +#ifdef NMEAGPS_INTERRUPT_PROCESSING + #error You must *NOT* define NMEAGPS_INTERRUPT_PROCESSING in NMEAGPS_cfg.h! +#endif + +//------------------------------------------------------------ + +static ubloxNMEA gps; // This parses received characters +static gps_fix merged; + +//---------------------------------------------------------------- + +static void poll() +{ + #if defined( NMEAGPS_PARSE_PUBX_00 ) + gps.send_P( &gpsPort, F("PUBX,00") ); + #endif + #if defined( NMEAGPS_PARSE_PUBX_04 ) + gps.send_P( &gpsPort, F("PUBX,04") ); + #endif +} + +//---------------------------------------------------------------- + +static void doSomeWork() +{ + // Print all the things! + trace_all( DEBUG_PORT, gps, merged ); + + // Ask for the proprietary messages again + poll(); + +} // doSomeWork + +//------------------------------------ + +static void GPSloop() +{ + while (gps.available( gpsPort )) { + merged = gps.read(); + + doSomeWork(); + } +} // GPSloop + +//-------------------------- + +void setup() +{ + DEBUG_PORT.begin(9600); + while (!DEBUG_PORT) + ; + + DEBUG_PORT.print( F("PUBX: started\n") ); + DEBUG_PORT.print( F("fix object size = ") ); + DEBUG_PORT.println( sizeof(gps.fix()) ); + DEBUG_PORT.print( F("ubloxNMEA object size = ") ); + DEBUG_PORT.println( sizeof(gps) ); + DEBUG_PORT.println( F("Looking for GPS device on " GPS_PORT_NAME) ); + + #ifndef NMEAGPS_PARSE_PUBX_00 + if (LAST_SENTENCE_IN_INTERVAL == (NMEAGPS::nmea_msg_t) ubloxNMEA::PUBX_00) { + DEBUG_PORT.println( F("ERROR! LAST_SENTENCE_IN_INTERVAL PUBX_00 not enabled!\n" + " Either change LAST_SENTENCE or enable PUBX_00") ); + for(;;); + } + #endif + #ifndef NMEAGPS_PARSE_PUBX_04 + if (LAST_SENTENCE_IN_INTERVAL == (NMEAGPS::nmea_msg_t) ubloxNMEA::PUBX_04) { + DEBUG_PORT.println( F("ERROR! LAST_SENTENCE_IN_INTERVAL PUBX_04 not enabled!\n" + " Either change LAST_SENTENCE or enable PUBX_04") ); + for(;;); + } + #endif + + trace_header( DEBUG_PORT ); + DEBUG_PORT.flush(); + + gpsPort.begin(9600); + + // Ask for the special PUBX sentences + poll(); +} + +//-------------------------- + +void loop() +{ + GPSloop(); +} diff --git a/software/firmware/libraries/NeoGPS/examples/SyncTime/SyncTime.ino b/software/firmware/libraries/NeoGPS/examples/SyncTime/SyncTime.ino new file mode 100644 index 0000000..b3ad7fb --- /dev/null +++ b/software/firmware/libraries/NeoGPS/examples/SyncTime/SyncTime.ino @@ -0,0 +1,137 @@ +#include + +//====================================================================== +// Program: SyncTime.ino +// +// Description: This program shows how to update the sub-second +// part of a clock's seconds. You can adjust the clock update +// interval to be as small as 9ms. It will calculate the +// correct ms offset from each GPS second. +// +// Prerequisites: +// 1) NMEA.ino works with your device +// 2) GPS_FIX_TIME is enabled in GPSfix_cfg.h +// 3) NMEAGPS_PARSE_RMC is enabled in NMEAGPS_cfg.h. You could use +// any sentence that contains a time field. Be sure to change the +// "if" statement in GPSloop from RMC to your selected sentence. +// +// 'Serial' is for debug output to the Serial Monitor window. +// +// License: +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . +// +//====================================================================== + +#include + +static NMEAGPS gps; +static gps_fix fix; + +#if !defined(GPS_FIX_TIME) + #error You must define GPS_FIX_TIME in GPSfix_cfg.h! +#endif + +#if !defined(NMEAGPS_PARSE_RMC) & \ + !defined(NMEAGPS_PARSE_GLL) & \ + !defined(NMEAGPS_PARSE_GGA) & \ + !defined(NMEAGPS_PARSE_GST) + #error You must define NMEAGPS_PARSE_RMC, GLL, GGA or GST in NMEAGPS_cfg.h! +#endif + +#if !defined(NMEAGPS_TIMESTAMP_FROM_INTERVAL) & \ + !defined(NMEAGPS_TIMESTAMP_FROM_PPS) + #error You must define NMEAGPS_TIMESTAMP_FROM_INTERVAL or PPS in NMEAGPS_cfg.h! +#endif + +#if defined(NMEAGPS_TIMESTAMP_FROM_PPS) + #warning You must modify this sketch to call gps.UTCsecondStart at the PPS rising edge (see NMEAGPS.h comments). +#endif + +#ifdef NMEAGPS_INTERRUPT_PROCESSING + #error You must *NOT* define NMEAGPS_INTERRUPT_PROCESSING in NMEAGPS_cfg.h! +#endif + +//---------------------------------------------------------------- + +static const uint32_t CLOCK_INTERVAL_MS = 100UL; +static uint32_t lastShowTime = CLOCK_INTERVAL_MS+1; // First time never matches + +//---------------------------------------------------------------- + +static void showTime( uint16_t subs, uint16_t factor = 100 /* hundredths */ ) +{ + uint8_t showSeconds = fix.dateTime.seconds; + + // Step by seconds until we're in the current UTC second + while (subs >= 1000UL) { + subs -= 1000UL; + if (showSeconds < 59) + showSeconds++; + else + showSeconds = 0; + //DEBUG_PORT.print( '+' ); + } + + DEBUG_PORT.print( showSeconds ); + DEBUG_PORT.print( '.' ); + + // Leading zeroes + for (;;) { + factor /= 10; + if ((factor < 10) || (subs >= factor)) + break; + DEBUG_PORT.print( '0' ); + } + + DEBUG_PORT.println( subs ); + +} // showTime + +//-------------------------- + +void setup() +{ + DEBUG_PORT.begin(9600); + while (!DEBUG_PORT) + ; + + DEBUG_PORT.print( F("SyncTime.INO: started\n") ); + DEBUG_PORT.println( F("Looking for GPS device on " GPS_PORT_NAME) ); + DEBUG_PORT.println( F("Local time seconds.milliseconds") ); + DEBUG_PORT.flush(); + + gpsPort.begin( 9600 ); +} + +//-------------------------- + +void loop() +{ + while (gps.available( gpsPort )) { + fix = gps.read(); + } + + if (fix.valid.time) { + uint32_t UTCms = gps.UTCms(); + + if (((UTCms % CLOCK_INTERVAL_MS) == 0) && (UTCms != lastShowTime)) { + showTime( UTCms, 1000 ); + lastShowTime = UTCms; + } + } +} diff --git a/software/firmware/libraries/NeoGPS/examples/Tabular/Tabular.ino b/software/firmware/libraries/NeoGPS/examples/Tabular/Tabular.ino new file mode 100644 index 0000000..e52c5db --- /dev/null +++ b/software/firmware/libraries/NeoGPS/examples/Tabular/Tabular.ino @@ -0,0 +1,198 @@ +#include + +NMEAGPS gps; + +//====================================================================== +// Program: SyncTime.ino +// +// Description: This program displays all GPS fields in the default configuration +// in a tabular display. To be comparable to other libraries' tabular displays, +// you must also enable HDOP in GPSfix_cfg.h. +// +// Most NeoGPS examples display *all* configured GPS fields in a CSV format +// (e.g., NMEA.ino). +// +// Prerequisites: +// 1) NMEA.ino works with your device (correct TX/RX pins and baud rate) +// 2) GPS_FIX_HDOP is defined in GPSfix_cfg.h +// +// 'Serial' is for debug output to the Serial Monitor window. +// +// License: +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . +// +//====================================================================== + +#include + +//----------------- +// Check configuration + +#ifndef GPS_FIX_HDOP + #error You must uncomment GPS_FIX_HDOP in GPSfix_cfg.h! +#endif + +//----------------- + +static const NeoGPS::Location_t London( 51.508131, -0.128002 ); + +void setup() +{ + DEBUG_PORT.begin(9600); + + DEBUG_PORT.println + ( + F( "Testing NeoGPS library\n\n" + "Sats HDOP Latitude Longitude Date Time Alt Speed Heading -- To London -- Chars Sentences Errors\n" + " (deg) (deg) (m) Dist Dir\n" ) + ); + + repeat( '-', 133 ); + + gpsPort.begin(9600); +} + +//----------------- + +void loop() +{ + if (gps.available( gpsPort )) { + gps_fix fix = gps.read(); + + float bearingToLondon = fix.location.BearingToDegrees( London ); + bool validDT = fix.valid.date & fix.valid.time; + + print( fix.satellites , fix.valid.satellites, 3 ); + print( fix.hdop/1000.0 , fix.valid.hdop , 6, 2 ); + print( fix.latitude () , fix.valid.location , 10, 6 ); + print( fix.longitude() , fix.valid.location , 11, 6 ); + print( fix.dateTime , validDT , 20 ); + print( fix.altitude () , fix.valid.altitude , 7, 2 ); + print( fix.speed_kph() , fix.valid.speed , 7, 2 ); + print( fix.heading () , fix.valid.heading , 7, 2 ); + print( compassDir( fix.heading () ) , fix.valid.heading , 4 ); + print( fix.location.DistanceKm( London ), fix.valid.location , 5 ); + print( bearingToLondon , fix.valid.location , 7, 2 ); + print( compassDir( bearingToLondon ) , fix.valid.location , 4 ); + + print( gps.statistics.chars , true, 10 ); + print( gps.statistics.ok , true, 6 ); + print( gps.statistics.errors, true, 6 ); + + DEBUG_PORT.println(); + } +} + +//----------------- +// Print utilities + +static void repeat( char c, int8_t len ) +{ + for (int8_t i=0; i= directions) + dir -= directions; + + return (const __FlashStringHelper *) pgm_read_ptr( &dirStrings[ dir ] ); + +} // compassDir diff --git a/software/firmware/libraries/NeoGPS/examples/ublox/ublox.ino b/software/firmware/libraries/NeoGPS/examples/ublox/ublox.ino new file mode 100644 index 0000000..d501fac --- /dev/null +++ b/software/firmware/libraries/NeoGPS/examples/ublox/ublox.ino @@ -0,0 +1,403 @@ +#include +#include + +//====================================================================== +// Program: ublox.ino +// +// Prerequisites: +// 1) You have a ublox GPS device +// 2) PUBX.ino works with your device +// 3) You have installed the ubxGPS.* and ubxmsg.* files. +// 4) At least one UBX message has been enabled in ubxGPS.h. +// 5) Implicit Merging is disabled in NMEAGPS_cfg.h. +// +// Description: This program parses UBX binary protocal messages from +// ublox devices. It shows how to acquire the information necessary +// to use the GPS Time-Of-Week in many UBX messages. As an offset +// from midnight Sunday morning (GPS time), you also need the current +// UTC time (this is *not* GPS time) and the current number of GPS +// leap seconds. +// +// Serial is for debug output to the Serial Monitor window. +// +// License: +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . +// +//====================================================================== + +#include + +#include + +//------------------------------------------------------------ +// Check that the config files are set up properly + +#ifndef NMEAGPS_DERIVED_TYPES + #error You must "#define NMEAGPS_DERIVED_TYPES" in NMEAGPS_cfg.h! +#endif + +#if !defined(UBLOX_PARSE_STATUS) & !defined(UBLOX_PARSE_TIMEGPS) & \ + !defined(UBLOX_PARSE_TIMEUTC) & !defined(UBLOX_PARSE_POSLLH) & \ + !defined(UBLOX_PARSE_VELNED) & !defined(UBLOX_PARSE_SVINFO) & \ + !defined(UBLOX_PARSE_DOP) + + #error No UBX binary messages enabled: no fix data available for fusing. + +#endif + +#if defined(UBLOX_PARSE_DOP) & \ + ( !defined(GPS_FIX_HDOP) & \ + !defined(GPS_FIX_VDOP) & \ + !defined(GPS_FIX_PDOP) ) + #warning UBX DOP message is enabled, but all GPS_fix DOP members are disabled. +#endif + +#ifndef NMEAGPS_RECOGNIZE_ALL + // Resetting the messages with ublox::configNMEA requires that + // all message types are recognized (i.e., the enum has all + // values). + #error You must "#define NMEAGPS_RECOGNIZE_ALL" in NMEAGPS_cfg.h! +#endif + +//----------------------------------------------------------------- +// Derive a class to add the state machine for starting up: +// 1) The status must change to something other than NONE. +// 2) The GPS leap seconds must be received +// 3) The UTC time must be received +// 4) All configured messages are "requested" +// (i.e., "enabled" in the ublox device) +// Then, all configured messages are parsed and explicitly merged. + +class MyGPS : public ubloxGPS +{ +public: + + enum + { + GETTING_STATUS, + GETTING_LEAP_SECONDS, + GETTING_UTC, + RUNNING + } + state NEOGPS_BF(8); + + MyGPS( Stream *device ) : ubloxGPS( device ) + { + state = GETTING_STATUS; + } + + //-------------------------- + + void get_status() + { + static bool acquiring = false; + + if (fix().status == gps_fix::STATUS_NONE) { + static uint32_t dotPrint; + bool requestNavStatus = false; + + if (!acquiring) { + acquiring = true; + dotPrint = millis(); + DEBUG_PORT.print( F("Acquiring...") ); + requestNavStatus = true; + + } else if (millis() - dotPrint > 1000UL) { + dotPrint = millis(); + DEBUG_PORT << '.'; + + static uint8_t requestPeriod; + if ((++requestPeriod & 0x07) == 0) + requestNavStatus = true; + } + + if (requestNavStatus) + // Turn on the UBX status message + enable_msg( ublox::UBX_NAV, ublox::UBX_NAV_STATUS ); + + } else { + if (acquiring) + DEBUG_PORT << '\n'; + DEBUG_PORT << F("Acquired status: ") << (uint8_t) fix().status << '\n'; + + #if defined(GPS_FIX_TIME) & defined(GPS_FIX_DATE) & \ + defined(UBLOX_PARSE_TIMEGPS) + + if (!enable_msg( ublox::UBX_NAV, ublox::UBX_NAV_TIMEGPS )) + DEBUG_PORT.println( F("enable TIMEGPS failed!") ); + + state = GETTING_LEAP_SECONDS; + #else + start_running(); + state = RUNNING; + #endif + } + } // get_status + + //-------------------------- + + void get_leap_seconds() + { + #if defined(GPS_FIX_TIME) & defined(GPS_FIX_DATE) & \ + defined(UBLOX_PARSE_TIMEGPS) + + if (GPSTime::leap_seconds != 0) { + DEBUG_PORT << F("Acquired leap seconds: ") << GPSTime::leap_seconds << '\n'; + + if (!disable_msg( ublox::UBX_NAV, ublox::UBX_NAV_TIMEGPS )) + DEBUG_PORT.println( F("disable TIMEGPS failed!") ); + + #if defined(UBLOX_PARSE_TIMEUTC) + if (!enable_msg( ublox::UBX_NAV, ublox::UBX_NAV_TIMEUTC )) + DEBUG_PORT.println( F("enable TIMEUTC failed!") ); + state = GETTING_UTC; + #else + start_running(); + #endif + } + #endif + + } // get_leap_seconds + + //-------------------------- + + void get_utc() + { + #if defined(GPS_FIX_TIME) & defined(GPS_FIX_DATE) & \ + defined(UBLOX_PARSE_TIMEUTC) + + lock(); + bool safe = is_safe(); + NeoGPS::clock_t sow = GPSTime::start_of_week(); + NeoGPS::time_t utc = fix().dateTime; + unlock(); + + if (safe && (sow != 0)) { + DEBUG_PORT << F("Acquired UTC: ") << utc << '\n'; + DEBUG_PORT << F("Acquired Start-of-Week: ") << sow << '\n'; + + start_running(); + } + #endif + + } // get_utc + + //-------------------------- + + void start_running() + { + bool enabled_msg_with_time = false; + + #if (defined(GPS_FIX_LOCATION) | \ + defined(GPS_FIX_LOCATION_DMS) | \ + defined(GPS_FIX_ALTITUDE)) & \ + defined(UBLOX_PARSE_POSLLH) + if (!enable_msg( ublox::UBX_NAV, ublox::UBX_NAV_POSLLH )) + DEBUG_PORT.println( F("enable POSLLH failed!") ); + + enabled_msg_with_time = true; + #endif + + #if (defined(GPS_FIX_SPEED) | defined(GPS_FIX_HEADING)) & \ + defined(UBLOX_PARSE_VELNED) + if (!enable_msg( ublox::UBX_NAV, ublox::UBX_NAV_VELNED )) + DEBUG_PORT.println( F("enable VELNED failed!") ); + + enabled_msg_with_time = true; + #endif + + #if defined(UBLOX_PARSE_DOP) + if (!enable_msg( ublox::UBX_NAV, ublox::UBX_NAV_DOP )) + DEBUG_PORT.println( F("enable DOP failed!") ); + else + DEBUG_PORT.println( F("enabled DOP.") ); + + enabled_msg_with_time = true; + #endif + + #if (defined(GPS_FIX_SATELLITES) | defined(NMEAGPS_PARSE_SATELLITES)) & \ + defined(UBLOX_PARSE_SVINFO) + if (!enable_msg( ublox::UBX_NAV, ublox::UBX_NAV_SVINFO )) + DEBUG_PORT.println( F("enable SVINFO failed!") ); + + enabled_msg_with_time = true; + #endif + + #if defined(UBLOX_PARSE_TIMEUTC) + + #if defined(GPS_FIX_TIME) & defined(GPS_FIX_DATE) + if (enabled_msg_with_time && + !disable_msg( ublox::UBX_NAV, ublox::UBX_NAV_TIMEUTC )) + DEBUG_PORT.println( F("disable TIMEUTC failed!") ); + + #elif defined(GPS_FIX_TIME) | defined(GPS_FIX_DATE) + // If both aren't defined, we can't convert TOW to UTC, + // so ask for the separate UTC message. + if (!enable_msg( ublox::UBX_NAV, ublox::UBX_NAV_TIMEUTC )) + DEBUG_PORT.println( F("enable TIMEUTC failed!") ); + #endif + + #endif + + state = RUNNING; + trace_header( DEBUG_PORT ); + + } // start_running + + //-------------------------- + + bool running() + { + switch (state) { + case GETTING_STATUS : get_status (); break; + case GETTING_LEAP_SECONDS: get_leap_seconds(); break; + case GETTING_UTC : get_utc (); break; + } + + return (state == RUNNING); + + } // running + +} NEOGPS_PACKED; + +// Construct the GPS object and hook it to the appropriate serial device +static MyGPS gps( &gpsPort ); + +#ifdef NMEAGPS_INTERRUPT_PROCESSING + static void GPSisr( uint8_t c ) + { + gps.handle( c ); + } +#endif + +//-------------------------- + +static void configNMEA( uint8_t rate ) +{ + for (uint8_t i=NMEAGPS::NMEA_FIRST_MSG; i<=NMEAGPS::NMEA_LAST_MSG; i++) { + ublox::configNMEA( gps, (NMEAGPS::nmea_msg_t) i, rate ); + } +} + +//-------------------------- + +static void disableUBX() +{ + gps.disable_msg( ublox::UBX_NAV, ublox::UBX_NAV_TIMEGPS ); + gps.disable_msg( ublox::UBX_NAV, ublox::UBX_NAV_TIMEUTC ); + gps.disable_msg( ublox::UBX_NAV, ublox::UBX_NAV_VELNED ); + gps.disable_msg( ublox::UBX_NAV, ublox::UBX_NAV_POSLLH ); + gps.disable_msg( ublox::UBX_NAV, ublox::UBX_NAV_DOP ); +} + +//-------------------------- + +void setup() +{ + // Start the normal trace output + DEBUG_PORT.begin(9600); + while (!DEBUG_PORT) + ; + + DEBUG_PORT.print( F("ublox binary protocol example started.\n") ); + DEBUG_PORT << F("fix object size = ") << sizeof(gps.fix()) << '\n'; + DEBUG_PORT << F("ubloxGPS object size = ") << sizeof(ubloxGPS) << '\n'; + DEBUG_PORT << F("MyGPS object size = ") << sizeof(gps) << '\n'; + DEBUG_PORT.println( F("Looking for GPS device on " GPS_PORT_NAME) ); + DEBUG_PORT.flush(); + + // Start the UART for the GPS device + #ifdef NMEAGPS_INTERRUPT_PROCESSING + gpsPort.attachInterrupt( GPSisr ); + #endif + gpsPort.begin(9600); + + // Turn off the preconfigured NMEA standard messages + configNMEA( 0 ); + + // Turn off things that may be left on by a previous build + disableUBX(); + + #if 0 + // Test a Neo M8 message -- should be rejected by Neo-6 and Neo7 + ublox::cfg_nmea_v1_t test; + + test.always_output_pos = false; // invalid or failed + test.output_invalid_pos = false; + test.output_invalid_time= false; + test.output_invalid_date= false; + test.use_GPS_only = false; + test.output_heading = false; // even if frozen + test.__not_used__ = false; + + test.nmea_version = ublox::cfg_nmea_v1_t::NMEA_V_4_0; + test.num_sats_per_talker_id = ublox::cfg_nmea_v1_t::SV_PER_TALKERID_UNLIMITED; + + test.compatibility_mode = false; + test.considering_mode = true; + test.max_line_length_82 = false; + test.__not_used_1__ = 0; + + test.filter_gps = false; + test.filter_sbas = false; + test.__not_used_2__= 0; + test.filter_qzss = false; + test.filter_glonass= false; + test.filter_beidou = false; + test.__not_used_3__= 0; + + test.proprietary_sat_numbering = false; + test.main_talker_id = ublox::cfg_nmea_v1_t::MAIN_TALKER_ID_GP; + test.gsv_uses_main_talker_id = true; + test.beidou_talker_id[0] = 'G'; + test.beidou_talker_id[1] = 'P'; + + DEBUG_PORT << F("CFG_NMEA result = ") << gps.send( test ); + #endif + + while (!gps.running()) + if (gps.available( gpsPort )) + gps.read(); +} + +//-------------------------- + +void loop() +{ + if (gps.available( gpsPort )) + trace_all( DEBUG_PORT, gps, gps.read() ); + + // If the user types something, reset the message configuration + // back to a normal set of NMEA messages. This makes it + // convenient to switch to another example program that + // expects a typical set of messages. This also saves + // putting those config messages in every other example. + + if (DEBUG_PORT.available()) { + do { DEBUG_PORT.read(); } while (DEBUG_PORT.available()); + DEBUG_PORT.println( F("Stopping...") ); + + configNMEA( 1 ); + disableUBX(); + gpsPort.flush(); + gpsPort.end(); + + DEBUG_PORT.println( F("STOPPED.") ); + for (;;); + } +} diff --git a/software/firmware/libraries/NeoGPS/examples/ubloxRate/ubloxRate.ino b/software/firmware/libraries/NeoGPS/examples/ubloxRate/ubloxRate.ino new file mode 100644 index 0000000..28407d9 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/examples/ubloxRate/ubloxRate.ino @@ -0,0 +1,369 @@ +#include +#include + +//====================================================================== +// Program: NMEA.ino +// +// Description: This program sends ublox commands to enable and disable +// NMEA sentences, set the update rate to 1Hz, 5Hz or 10Hz, and set the +// baud rate to 9600 or 115200. +// +// Enter the following commands through the Serial Monitor window: +// +// '1' - send NMEA PUBX text command to enable all sentences +// '0' - send NMEA PUBX text command to disable all sentences except GLL +// 'd' - send UBX binary command to disable all sentences except GLL +// 'r1' - send UBX binary command to set update rate to 1Hz +// 'r5' - send UBX binary command to set update rate to 5Hz +// 'r0' - send UBX binary command to set update rate to 10Hz +// 'r6' - send UBX binary command to set update rate to 16Hz +// '5' - send NMEA PUBX text command to set baud rate to 115200 +// '7' - send NMEA PUBX text command to set baud rate to 57600 +// '3' - send NMEA PUBX text command to set baud rate to 38400 +// '9' - send NMEA PUBX text command to set baud rate to 9600 +// 'e' - toggle echo of all characters received from GPS device. +// +// CAUTION: If your Serial Monitor window baud rate is less than the GPS baud +// rate, turning echo ON will cause the sketch to lose some or all +// GPS data and/or fixes. +// +// NOTE: All NMEA PUBX text commands are also echoed to the debug port. +// +// Prerequisites: +// 1) Your GPS device has been correctly powered. +// Be careful when connecting 3.3V devices. +// 2) Your GPS device is correctly connected to an Arduino serial port. +// See GPSport.h for the default connections. +// 3) You know the default baud rate of your GPS device. +// If 9600 does not work, use NMEAdiagnostic.ino to +// scan for the correct baud rate. +// 4) LAST_SENTENCE_IN_INTERVAL is defined to be the following in NMEAGPS_cfg.h: +// +// #include +// extern uint8_t LastSentenceInInterval; // a variable! +// #define LAST_SENTENCE_IN_INTERVAL \ +// ((NMEAGPS::nmea_msg_t) LastSentenceInInterval) +// +// This is a replacement for the typical +// +// #define LAST_SENTENCE_IN_INTERVAL NMEAGPS::NMEA_GLL +// +// This allows the sketch to choose the last sentence *at run time*, not +// compile time. This is necessary because this sketch can send +// configuration commands that change which sentences are enabled at run +// time. The storage for the "externed" variable is below. +// +// 'Serial' is for debug output to the Serial Monitor window. +// +// License: +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . +// +//====================================================================== + +#include + +#include + +static NMEAGPS gps; +static gps_fix fix_data; +uint8_t LastSentenceInInterval = 0xFF; // storage for the run-time selection + +static char lastChar; // last command char +static bool echoing = false; + +// Use NeoTee to echo the NMEA text commands to the Serial Monitor window +Stream *both[2] = { &DEBUG_PORT, &gpsPort }; +NeoTeeStream tee( both, sizeof(both)/sizeof(both[0]) ); + +//------------------------------------------- +// U-blox UBX binary commands + +const unsigned char ubxRate1Hz[] PROGMEM = + { 0x06,0x08,0x06,0x00,0xE8,0x03,0x01,0x00,0x01,0x00 }; +const unsigned char ubxRate5Hz[] PROGMEM = + { 0x06,0x08,0x06,0x00,200,0x00,0x01,0x00,0x01,0x00 }; +const unsigned char ubxRate10Hz[] PROGMEM = + { 0x06,0x08,0x06,0x00,100,0x00,0x01,0x00,0x01,0x00 }; +const unsigned char ubxRate16Hz[] PROGMEM = + { 0x06,0x08,0x06,0x00,50,0x00,0x01,0x00,0x01,0x00 }; + +// Disable specific NMEA sentences +const unsigned char ubxDisableGGA[] PROGMEM = + { 0x06,0x01,0x08,0x00,0xF0,0x00,0x00,0x00,0x00,0x00,0x00,0x01 }; +const unsigned char ubxDisableGLL[] PROGMEM = + { 0x06,0x01,0x08,0x00,0xF0,0x01,0x00,0x00,0x00,0x00,0x00,0x01 }; +const unsigned char ubxDisableGSA[] PROGMEM = + { 0x06,0x01,0x08,0x00,0xF0,0x02,0x00,0x00,0x00,0x00,0x00,0x01 }; +const unsigned char ubxDisableGSV[] PROGMEM = + { 0x06,0x01,0x08,0x00,0xF0,0x03,0x00,0x00,0x00,0x00,0x00,0x01 }; +const unsigned char ubxDisableRMC[] PROGMEM = + { 0x06,0x01,0x08,0x00,0xF0,0x04,0x00,0x00,0x00,0x00,0x00,0x01 }; +const unsigned char ubxDisableVTG[] PROGMEM = + { 0x06,0x01,0x08,0x00,0xF0,0x05,0x00,0x00,0x00,0x00,0x00,0x01 }; +const unsigned char ubxDisableZDA[] PROGMEM = + { 0x06,0x01,0x08,0x00,0xF0,0x08,0x00,0x00,0x00,0x00,0x00,0x01 }; + +//-------------------------- + +void sendUBX( const unsigned char *progmemBytes, size_t len ) +{ + gpsPort.write( 0xB5 ); // SYNC1 + gpsPort.write( 0x62 ); // SYNC2 + + uint8_t a = 0, b = 0; + while (len-- > 0) { + uint8_t c = pgm_read_byte( progmemBytes++ ); + a += c; + b += a; + gpsPort.write( c ); + } + + gpsPort.write( a ); // CHECKSUM A + gpsPort.write( b ); // CHECKSUM B + +} // sendUBX + +//------------------------------------------- +// U-blox NMEA text commands + +const char disableRMC[] PROGMEM = "PUBX,40,RMC,0,0,0,0,0,0"; +const char disableGLL[] PROGMEM = "PUBX,40,GLL,0,0,0,0,0,0"; +const char disableGSV[] PROGMEM = "PUBX,40,GSV,0,0,0,0,0,0"; +const char disableGSA[] PROGMEM = "PUBX,40,GSA,0,0,0,0,0,0"; +const char disableGGA[] PROGMEM = "PUBX,40,GGA,0,0,0,0,0,0"; +const char disableVTG[] PROGMEM = "PUBX,40,VTG,0,0,0,0,0,0"; +const char disableZDA[] PROGMEM = "PUBX,40,ZDA,0,0,0,0,0,0"; + +const char enableRMC[] PROGMEM = "PUBX,40,RMC,0,1,0,0,0,0"; +const char enableGLL[] PROGMEM = "PUBX,40,GLL,0,1,0,0,0,0"; +const char enableGSV[] PROGMEM = "PUBX,40,GSV,0,1,0,0,0,0"; +const char enableGSA[] PROGMEM = "PUBX,40,GSA,0,1,0,0,0,0"; +const char enableGGA[] PROGMEM = "PUBX,40,GGA,0,1,0,0,0,0"; +const char enableVTG[] PROGMEM = "PUBX,40,VTG,0,1,0,0,0,0"; +const char enableZDA[] PROGMEM = "PUBX,40,ZDA,0,1,0,0,0,0"; + +const char baud9600 [] PROGMEM = "PUBX,41,1,3,3,9600,0"; +const char baud38400 [] PROGMEM = "PUBX,41,1,3,3,38400,0"; +const char baud57600 [] PROGMEM = "PUBX,41,1,3,3,57600,0"; +const char baud115200[] PROGMEM = "PUBX,41,1,3,3,115200,0"; + +//-------------------------- + +const uint32_t COMMAND_DELAY = 250; + +void changeBaud( const char *textCommand, unsigned long baud ) +{ + gps.send_P( &tee, (const __FlashStringHelper *) disableRMC ); + delay( COMMAND_DELAY ); +// gps.send_P( &tee, (const __FlashStringHelper *) disableGLL ); +// delay( COMMAND_DELAY ); + gps.send_P( &tee, (const __FlashStringHelper *) disableGSV ); + delay( COMMAND_DELAY ); + gps.send_P( &tee, (const __FlashStringHelper *) disableGSA ); + delay( COMMAND_DELAY ); + gps.send_P( &tee, (const __FlashStringHelper *) disableGGA ); + delay( COMMAND_DELAY ); + gps.send_P( &tee, (const __FlashStringHelper *) disableVTG ); + delay( COMMAND_DELAY ); + gps.send_P( &tee, (const __FlashStringHelper *) disableZDA ); + delay( 500 ); + gps.send_P( &tee, (const __FlashStringHelper *) textCommand ); + gpsPort.flush(); + gpsPort.end(); + + DEBUG_PORT.print( F("All sentences disabled for baud rate ") ); + DEBUG_PORT.print( baud ); + DEBUG_PORT.println( F(" change. Enter '1' to reenable sentences.") ); + delay( 500 ); + gpsPort.begin( baud ); + +} // changeBaud + +//------------------------------------ + +static void doSomeWork() +{ + // Print all the things! + + trace_all( DEBUG_PORT, gps, fix_data ); + +} // doSomeWork + +//-------------------------- + +void setup() +{ + DEBUG_PORT.begin(9600); + while (!DEBUG_PORT) + ; + + DEBUG_PORT.print( F("ubloxRate.INO: started\n") ); + DEBUG_PORT.println( F("Looking for GPS device on " GPS_PORT_NAME) ); + + #ifdef NMEAGPS_INTERRUPT_PROCESSING + #error You must *NOT* define NMEAGPS_INTERRUPT_PROCESSING in NMEAGPS_cfg.h! + #endif + + #if !defined( NMEAGPS_PARSE_GGA ) & !defined( NMEAGPS_PARSE_GLL ) & \ + !defined( NMEAGPS_PARSE_GSA ) & !defined( NMEAGPS_PARSE_GSV ) & \ + !defined( NMEAGPS_PARSE_RMC ) & !defined( NMEAGPS_PARSE_VTG ) & \ + !defined( NMEAGPS_PARSE_ZDA ) & !defined( NMEAGPS_PARSE_GST ) + + DEBUG_PORT.println( F("\nWARNING: No NMEA sentences are enabled: no fix data will be displayed.") ); + + #else + if (gps.merging == NMEAGPS::NO_MERGING) { + DEBUG_PORT.print ( F("\nWARNING: displaying data from ") ); + DEBUG_PORT.print ( gps.string_for( LAST_SENTENCE_IN_INTERVAL ) ); + DEBUG_PORT.print ( F(" sentences ONLY, and only if ") ); + DEBUG_PORT.print ( gps.string_for( LAST_SENTENCE_IN_INTERVAL ) ); + DEBUG_PORT.println( F(" is enabled.\n" + " Other sentences may be parsed, but their data will not be displayed.") ); + } + #endif + + if (LastSentenceInInterval != LAST_SENTENCE_IN_INTERVAL) { + DEBUG_PORT.println( + F("LAST_SENTENCE_IN_INTERVAL is not properly defined in NMEAGPS_cfg.h!\n" + " See Prerequisite 4 above") ); + } + LastSentenceInInterval = NMEAGPS::NMEA_GLL; + + trace_header( DEBUG_PORT ); + DEBUG_PORT.flush(); + + gpsPort.begin( 9600 ); +} + +void loop() +{ + // Check for commands + + if (DEBUG_PORT.available()) { + char c = DEBUG_PORT.read(); + + switch (c) { + case '0': + if (lastChar == 'r') { + sendUBX( ubxRate10Hz, sizeof(ubxRate10Hz) ); + } else { + gps.send_P( &tee, (const __FlashStringHelper *) disableRMC ); + delay( COMMAND_DELAY ); + gps.send_P( &tee, (const __FlashStringHelper *) enableGLL ); + delay( COMMAND_DELAY ); + gps.send_P( &tee, (const __FlashStringHelper *) disableGSV ); + delay( COMMAND_DELAY ); + gps.send_P( &tee, (const __FlashStringHelper *) disableGSA ); + delay( COMMAND_DELAY ); + gps.send_P( &tee, (const __FlashStringHelper *) disableGGA ); + delay( COMMAND_DELAY ); + gps.send_P( &tee, (const __FlashStringHelper *) disableVTG ); + delay( COMMAND_DELAY ); + gps.send_P( &tee, (const __FlashStringHelper *) disableZDA ); + LastSentenceInInterval = NMEAGPS::NMEA_GLL; + } + break; + case '1': + if (lastChar == 'r') { + sendUBX( ubxRate1Hz, sizeof(ubxRate1Hz) ); + } else { + gps.send_P( &tee, (const __FlashStringHelper *) enableRMC ); + delay( COMMAND_DELAY ); + gps.send_P( &tee, (const __FlashStringHelper *) enableGLL ); + delay( COMMAND_DELAY ); + gps.send_P( &tee, (const __FlashStringHelper *) enableGSV ); + delay( COMMAND_DELAY ); + gps.send_P( &tee, (const __FlashStringHelper *) enableGSA ); + delay( COMMAND_DELAY ); + gps.send_P( &tee, (const __FlashStringHelper *) enableGGA ); + delay( COMMAND_DELAY ); + gps.send_P( &tee, (const __FlashStringHelper *) enableVTG ); + delay( COMMAND_DELAY ); + gps.send_P( &tee, (const __FlashStringHelper *) enableZDA ); + LastSentenceInInterval = NMEAGPS::NMEA_ZDA; + } + break; + case '3': + changeBaud( baud38400, 38400UL ); + break; + case '5': + if (lastChar == 'r') { + sendUBX( ubxRate5Hz, sizeof(ubxRate5Hz) ); + } else + changeBaud( baud115200, 115200UL ); + break; + case '6': + if (lastChar == 'r') { + sendUBX( ubxRate16Hz, sizeof(ubxRate16Hz) ); + } + break; + case '7': + changeBaud( baud57600, 57600UL ); + break; + case '9': + changeBaud( baud9600, 9600UL ); + break; + + case 'd': + sendUBX( ubxDisableRMC, sizeof(ubxDisableRMC) ); + delay( COMMAND_DELAY ); + //sendUBX( ubxDisableGLL, sizeof(ubxDisableGLL) ); + sendUBX( ubxDisableGSV, sizeof(ubxDisableGSV) ); + delay( COMMAND_DELAY ); + sendUBX( ubxDisableGSA, sizeof(ubxDisableGSA) ); + delay( COMMAND_DELAY ); + sendUBX( ubxDisableGGA, sizeof(ubxDisableGGA) ); + delay( COMMAND_DELAY ); + sendUBX( ubxDisableVTG, sizeof(ubxDisableVTG) ); + delay( COMMAND_DELAY ); + sendUBX( ubxDisableZDA, sizeof(ubxDisableZDA) ); + LastSentenceInInterval = NMEAGPS::NMEA_GLL; + break; + + case 'e': + echoing = !echoing; + break; + + default: break; + } + lastChar = c; + } + + // Check for GPS data + + if (echoing) { + // Use advanced character-oriented methods to echo received characters to + // the Serial Monitor window. + if (gpsPort.available()) { + char c = gpsPort.read(); + DEBUG_PORT.write( c ); + gps.handle( c ); + if (gps.available()) { + fix_data = gps.read(); + doSomeWork(); + } + } + + } else { + // Use the normal fix-oriented methods to display fixes + if (gps.available( gpsPort )) { + fix_data = gps.read(); + doSomeWork(); + } + } +} diff --git a/software/firmware/libraries/NeoGPS/extras/configs/DTL/GPSfix_cfg.h b/software/firmware/libraries/NeoGPS/extras/configs/DTL/GPSfix_cfg.h new file mode 100644 index 0000000..3876fa3 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/configs/DTL/GPSfix_cfg.h @@ -0,0 +1,35 @@ +#ifndef GPS_FIX_CFG +#define GPS_FIX_CFG + +/** + * Enable/disable the storage for the members of a fix. + * + * Disabling a member prevents it from being parsed from a received message. + * The disabled member cannot be accessed or stored, and its validity flag + * would not be available. It will not be declared, and code that uses that + * member will not compile. + * + * DATE and TIME are somewhat coupled in that they share a single `time_t`, + * but they have separate validity flags. + * + * See also note regarding the DOP members, below. + * + */ + +#define GPS_FIX_DATE +#define GPS_FIX_TIME +#define GPS_FIX_LOCATION +//#define GPS_FIX_LOCATION_DMS +//#define GPS_FIX_ALTITUDE +//#define GPS_FIX_SPEED +//#define GPS_FIX_HEADING +//#define GPS_FIX_SATELLITES +//#define GPS_FIX_HDOP +//#define GPS_FIX_VDOP +//#define GPS_FIX_PDOP +//#define GPS_FIX_LAT_ERR +//#define GPS_FIX_LON_ERR +//#define GPS_FIX_ALT_ERR +//#define GPS_FIX_GEOID_HEIGHT + +#endif diff --git a/software/firmware/libraries/NeoGPS/extras/configs/DTL/NMEAGPS_cfg.h b/software/firmware/libraries/NeoGPS/extras/configs/DTL/NMEAGPS_cfg.h new file mode 100644 index 0000000..bbf7b80 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/configs/DTL/NMEAGPS_cfg.h @@ -0,0 +1,286 @@ +#ifndef NMEAGPS_CFG_H +#define NMEAGPS_CFG_H + +//------------------------------------------------------ +// Enable/disable the parsing of specific sentences. +// +// Configuring out a sentence prevents it from being recognized; it +// will be completely ignored. (See also NMEAGPS_RECOGNIZE_ALL, below) +// +// FYI: Only RMC and ZDA contain date information. Other +// sentences contain time information. Both date and time are +// required if you will be doing time_t-to-clock_t operations. + +//#define NMEAGPS_PARSE_GGA +//#define NMEAGPS_PARSE_GLL +//#define NMEAGPS_PARSE_GSA +//#define NMEAGPS_PARSE_GSV +//#define NMEAGPS_PARSE_GST +#define NMEAGPS_PARSE_RMC +//#define NMEAGPS_PARSE_VTG +//#define NMEAGPS_PARSE_ZDA + +//------------------------------------------------------ +// Select which sentence is sent *last* by your GPS device +// in each update interval. This can be used by your sketch +// to determine when the GPS quiet time begins, and thus +// when you can perform "some" time-consuming operations. + +#define LAST_SENTENCE_IN_INTERVAL NMEAGPS::NMEA_RMC + +// If the NMEA_LAST_SENTENCE_IN_INTERVAL is not chosen +// correctly, GPS data may be lost because the sketch +// takes too long elsewhere when this sentence is received. +// Also, fix members may contain information from different +// time intervals (i.e., they are not coherent). +// +// If you don't know which sentence is the last one, +// use NMEAorder.ino to list them. You do not have to select +// the last sentence the device sends if you have disabled +// it. Just select the last sentence that you have *enabled*. + +//------------------------------------------------------ +// Enable/Disable coherency: +// +// If you need each fix to contain information that is only +// from the current update interval, you should uncomment +// this define. At the beginning of the next interval, +// the accumulating fix will start out empty. When +// the LAST_SENTENCE_IN_INTERVAL arrives, the valid +// fields will be coherent. + +//#define NMEAGPS_COHERENT + +// With IMPLICIT merging, fix() will be emptied when the +// next sentence begins. +// +// With EXPLICIT or NO merging, the fix() was already +// being initialized. +// +// If you use the fix-oriented methods available() and read(), +// they will empty the current fix for you automatically. +// +// If you use the character-oriented method decode(), you should +// empty the accumulating fix by testing and clearing the +// 'intervalComplete' flag in the same way that available() does. + +//------------------------------------------------------ +// Choose how multiple sentences are merged: +// 1) No merging +// Each sentence fills out its own fix; there could be +// multiple sentences per interval. +// 2) EXPLICIT_MERGING +// All sentences in an interval are *safely* merged into one fix. +// NMEAGPS_FIX_MAX must be >= 1. +// An interval is defined by NMEA_LAST_SENTENCE_IN_INTERVAL. +// 3) IMPLICIT_MERGING +// All sentences in an interval are merged into one fix, with +// possible data loss. If a received sentence is rejected for +// any reason (e.g., a checksum error), all the values are suspect. +// The fix will be cleared; no members will be valid until new +// sentences are received and accepted. This uses less RAM. +// An interval is defined by NMEA_LAST_SENTENCE_IN_INTERVAL. +// Uncomment zero or one: + +#define NMEAGPS_EXPLICIT_MERGING +//#define NMEAGPS_IMPLICIT_MERGING + +#ifdef NMEAGPS_IMPLICIT_MERGING + #define NMEAGPS_MERGING NMEAGPS::IMPLICIT_MERGING + + // When accumulating, nothing is done to the fix at the + // beginning of every sentence... + #ifdef NMEAGPS_COHERENT + // ...unless COHERENT is enabled and a new interval is starting + #define NMEAGPS_INIT_FIX(m) \ + if (intervalComplete()) { intervalComplete( false ); m.valid.init(); } + #else + #define NMEAGPS_INIT_FIX(m) + #endif + + // ...but we invalidate one part when it starts to get parsed. It *may* get + // validated when the parsing is finished. + #define NMEAGPS_INVALIDATE(m) m_fix.valid.m = false + +#else + + #ifdef NMEAGPS_EXPLICIT_MERGING + #define NMEAGPS_MERGING NMEAGPS::EXPLICIT_MERGING + #else + #define NMEAGPS_MERGING NMEAGPS::NO_MERGING + #define NMEAGPS_NO_MERGING + #endif + + // When NOT accumulating, invalidate the entire fix at the + // beginning of every sentence + #define NMEAGPS_INIT_FIX(m) m.valid.init() + + // ...so the individual parts do not need to be invalidated as they are parsed + #define NMEAGPS_INVALIDATE(m) + +#endif + +#if ( defined(NMEAGPS_NO_MERGING) + \ + defined(NMEAGPS_IMPLICIT_MERGING) + \ + defined(NMEAGPS_EXPLICIT_MERGING) ) > 1 + #error Only one MERGING technique should be enabled in NMEAGPS_cfg.h! +#endif + +//------------------------------------------------------ +// Define the fix buffer size. The NMEAGPS object will hold on to +// this many fixes before an overrun occurs. This can be zero, +// but you have to be more careful about using gps.fix() structure, +// because it will be modified as characters are received. + +#define NMEAGPS_FIX_MAX 1 + +#if defined(NMEAGPS_EXPLICIT_MERGING) && (NMEAGPS_FIX_MAX == 0) + #error You must define FIX_MAX >= 1 to allow EXPLICIT merging in NMEAGPS_cfg.h +#endif + +//------------------------------------------------------ +// Enable/Disable interrupt-style processing of GPS characters +// If you are using one of the NeoXXSerial libraries, +// to attachInterrupt, this must be defined. +// Otherwise, it must be commented out. + +//#define NMEAGPS_INTERRUPT_PROCESSING + +#ifdef NMEAGPS_INTERRUPT_PROCESSING + #define NMEAGPS_PROCESSING_STYLE NMEAGPS::PS_INTERRUPT +#else + #define NMEAGPS_PROCESSING_STYLE NMEAGPS::PS_POLLING +#endif + +//------------------------------------------------------ +// Enable/disable the talker ID, manufacturer ID and proprietary message processing. +// +// First, some background information. There are two kinds of NMEA sentences: +// +// 1. Standard NMEA sentences begin with "$ttccc", where +// "tt" is the talker ID, and +// "ccc" is the variable-length sentence type (i.e., command). +// +// For example, "$GPGLL,..." is a GLL sentence (Geographic Lat/Long) +// transmitted by talker "GP". This is the most common talker ID. Some +// devices may report "$GNGLL,..." when a mix of GPS and non-GPS +// satellites have been used to determine the GLL data. +// +// 2. Proprietary NMEA sentences (i.e., those unique to a particular +// manufacturer) begin with "$Pmmmccc", where +// "P" is the NMEA-defined prefix indicator for proprietary messages, +// "mmm" is the 3-character manufacturer ID, and +// "ccc" is the variable-length sentence type (it can be empty). +// +// No validation of manufacturer ID and talker ID is performed in this +// base class. For example, although "GP" is a common talker ID, it is not +// guaranteed to be transmitted by your particular device, and it IS NOT +// REQUIRED. If you need validation of these IDs, or you need to use the +// extra information provided by some devices, you have two independent +// options: +// +// 1. Enable SAVING the ID: When /decode/ returns DECODE_COMPLETED, the +// /talker_id/ and/or /mfr_id/ members will contain ID bytes. The entire +// sentence will be parsed, perhaps modifying members of /fix/. You should +// enable one or both IDs if you want the information in all sentences *and* +// you also want to know the ID bytes. This adds two bytes of RAM for the +// talker ID, and 3 bytes of RAM for the manufacturer ID. +// +// 2. Enable PARSING the ID: The virtual /parse_talker_id/ and +// /parse_mfr_id/ will receive each ID character as it is parsed. If it +// is not a valid ID, return /false/ to abort processing the rest of the +// sentence. No CPU time will be wasted on the invalid sentence, and no +// /fix/ members will be modified. You should enable this if you want to +// ignore some IDs. You must override /parse_talker_id/ and/or +// /parse_mfr_id/ in a derived class. +// + +//#define NMEAGPS_SAVE_TALKER_ID +//#define NMEAGPS_PARSE_TALKER_ID + +//#define NMEAGPS_PARSE_PROPRIETARY +#ifdef NMEAGPS_PARSE_PROPRIETARY + //#define NMEAGPS_SAVE_MFR_ID + #define NMEAGPS_PARSE_MFR_ID +#endif + +//------------------------------------------------------ +// Enable/disable tracking the current satellite array and, +// optionally, all the info for each satellite. +// + +//#define NMEAGPS_PARSE_SATELLITES +//#define NMEAGPS_PARSE_SATELLITE_INFO + +#ifdef NMEAGPS_PARSE_SATELLITES + #define NMEAGPS_MAX_SATELLITES (20) + + #ifndef GPS_FIX_SATELLITES + #error GPS_FIX_SATELLITES must be defined in GPSfix.h! + #endif + +#endif + +#if defined(NMEAGPS_PARSE_SATELLITE_INFO) & \ + !defined(NMEAGPS_PARSE_SATELLITES) + #error NMEAGPS_PARSE_SATELLITES must be defined! +#endif + +//------------------------------------------------------ +// Enable/disable gathering interface statistics: +// CRC errors and number of sentences received + +#define NMEAGPS_STATS + +//------------------------------------------------------ +// Configuration item for allowing derived types of NMEAGPS. +// If you derive classes from NMEAGPS, you *must* define NMEAGPS_DERIVED_TYPES. +// If not defined, virtuals are not used, with a slight size (2 bytes) and +// execution time savings. + +//#define NMEAGPS_DERIVED_TYPES + +#ifdef NMEAGPS_DERIVED_TYPES + #define NMEAGPS_VIRTUAL virtual +#else + #define NMEAGPS_VIRTUAL +#endif + +//----------------------------------- +// See if DERIVED_TYPES is required +#if (defined(NMEAGPS_PARSE_TALKER_ID) | defined(NMEAGPS_PARSE_MFR_ID)) & \ + !defined(NMEAGPS_DERIVED_TYPES) + #error You must define NMEAGPS_DERIVED_TYPES in NMEAGPS.h in order to parse Talker and/or Mfr IDs! +#endif + +//------------------------------------------------------ +// Some devices may omit trailing commas at the end of some +// sentences. This may prevent the last field from being +// parsed correctly, because the parser for some types keep +// the value in an intermediate state until the complete +// field is received (e.g., parseDDDMM, parseFloat and +// parseZDA). +// +// Enabling this will inject a simulated comma when the end +// of a sentence is received and the last field parser +// indicated that it still needs one. + +//#define NMEAGPS_COMMA_NEEDED + +//------------------------------------------------------ +// Some applications may want to recognize a sentence type +// without actually parsing any of the fields. Uncommenting +// this define will allow the nmeaMessage member to be set +// when *any* standard message is seen, even though that +// message is not enabled by a NMEAGPS_PARSE_xxx define above. +// No valid flags will be true for those sentences. + +#define NMEAGPS_RECOGNIZE_ALL + +//------------------------------------------------------ +// Sometimes, a little extra space is needed to parse an intermediate form. +// This config items enables extra space. + +//#define NMEAGPS_PARSING_SCRATCHPAD + +#endif \ No newline at end of file diff --git a/software/firmware/libraries/NeoGPS/extras/configs/DTL/NeoGPS_cfg.h b/software/firmware/libraries/NeoGPS/extras/configs/DTL/NeoGPS_cfg.h new file mode 100644 index 0000000..7ad6b70 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/configs/DTL/NeoGPS_cfg.h @@ -0,0 +1,85 @@ +#ifndef NEOGPS_CFG +#define NEOGPS_CFG + +/** + * Enable/disable packed data structures. + * + * Enabling packed data structures will use two less-portable language + * features of GCC to reduce RAM requirements. Although it was expected to slightly increase execution time and code size, the reverse is true on 8-bit AVRs: the code is smaller and faster with packing enabled. + * + * Disabling packed data structures will be very portable to other + * platforms. NeoGPS configurations will use slightly more RAM, and on + * 8-bit AVRs, the speed is slightly slower, and the code is slightly + * larger. There may be no choice but to disable packing on processors + * that do not support packed structures. + * + * There may also be compiler-specific switches that affect packing and the + * code which accesses packed members. YMMV. + **/ + +#ifdef __AVR__ + #define NEOGPS_PACKED_DATA +#endif + +//------------------------------------------------------------------------ +// Based on the above define, choose which set of packing macros should +// be used in the rest of the NeoGPS package. Do not change these defines. + +#ifdef NEOGPS_PACKED_DATA + + // This is for specifying the number of bits to be used for a + // member of a struct. Booleans are typically one bit. + #define NEOGPS_BF(b) :b + + // This is for requesting the compiler to pack the struct or class members + // "as closely as possible". This is a compiler-dependent interpretation. + #define NEOGPS_PACKED __attribute__((packed)) + +#else + + // Let the compiler do whatever it wants. + + #define NEOGPS_PACKED + #define NEOGPS_BF(b) + +#endif + +/* + * Accommodate C++ compiler and IDE changes. + * + * Declaring constants as class data instead of instance data helps avoid + * collisions with #define names, and allows the compiler to perform more + * checks on their usage. + * + * Until C++ 10 and IDE 1.6.8, initialized class data constants + * were declared like this: + * + * static const = ; + * + * Now, non-simple types (e.g., float) must be declared as + * + * static constexpr = ; + * + * The good news is that this allows the compiler to optimize out an + * expression that is "promised" to be "evaluatable" as a constant. + * The bad news is that it introduces a new language keyword, and the old + * code raises an error. + * + * TODO: Evaluate the requirement for the "static" keyword. + * TODO: Evaluate using a C++ version preprocessor symbol for the #if. + * + * The CONST_CLASS_DATA define will expand to the appropriate keywords. + * + */ + +#if ARDUINO < 10606 + + #define CONST_CLASS_DATA static const + +#else + + #define CONST_CLASS_DATA static constexpr + +#endif + +#endif diff --git a/software/firmware/libraries/NeoGPS/extras/configs/Full/GPSfix_cfg.h b/software/firmware/libraries/NeoGPS/extras/configs/Full/GPSfix_cfg.h new file mode 100644 index 0000000..94b3445 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/configs/Full/GPSfix_cfg.h @@ -0,0 +1,35 @@ +#ifndef GPS_FIX_CFG +#define GPS_FIX_CFG + +/** + * Enable/disable the storage for the members of a fix. + * + * Disabling a member prevents it from being parsed from a received message. + * The disabled member cannot be accessed or stored, and its validity flag + * would not be available. It will not be declared, and code that uses that + * member will not compile. + * + * DATE and TIME are somewhat coupled in that they share a single `time_t`, + * but they have separate validity flags. + * + * See also note regarding the DOP members, below. + * + */ + +#define GPS_FIX_DATE +#define GPS_FIX_TIME +#define GPS_FIX_LOCATION +#define GPS_FIX_LOCATION_DMS +#define GPS_FIX_ALTITUDE +#define GPS_FIX_SPEED +#define GPS_FIX_HEADING +#define GPS_FIX_SATELLITES +#define GPS_FIX_HDOP +#define GPS_FIX_VDOP +#define GPS_FIX_PDOP +#define GPS_FIX_LAT_ERR +#define GPS_FIX_LON_ERR +#define GPS_FIX_ALT_ERR +#define GPS_FIX_GEOID_HEIGHT + +#endif diff --git a/software/firmware/libraries/NeoGPS/extras/configs/Full/NMEAGPS_cfg.h b/software/firmware/libraries/NeoGPS/extras/configs/Full/NMEAGPS_cfg.h new file mode 100644 index 0000000..5ead36f --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/configs/Full/NMEAGPS_cfg.h @@ -0,0 +1,286 @@ +#ifndef NMEAGPS_CFG_H +#define NMEAGPS_CFG_H + +//------------------------------------------------------ +// Enable/disable the parsing of specific sentences. +// +// Configuring out a sentence prevents it from being recognized; it +// will be completely ignored. (See also NMEAGPS_RECOGNIZE_ALL, below) +// +// FYI: Only RMC and ZDA contain date information. Other +// sentences contain time information. Both date and time are +// required if you will be doing time_t-to-clock_t operations. + +#define NMEAGPS_PARSE_GGA +#define NMEAGPS_PARSE_GLL +#define NMEAGPS_PARSE_GSA +#define NMEAGPS_PARSE_GSV +#define NMEAGPS_PARSE_GST +#define NMEAGPS_PARSE_RMC +#define NMEAGPS_PARSE_VTG +#define NMEAGPS_PARSE_ZDA + +//------------------------------------------------------ +// Select which sentence is sent *last* by your GPS device +// in each update interval. This can be used by your sketch +// to determine when the GPS quiet time begins, and thus +// when you can perform "some" time-consuming operations. + +#define LAST_SENTENCE_IN_INTERVAL NMEAGPS::NMEA_RMC + +// If the NMEA_LAST_SENTENCE_IN_INTERVAL is not chosen +// correctly, GPS data may be lost because the sketch +// takes too long elsewhere when this sentence is received. +// Also, fix members may contain information from different +// time intervals (i.e., they are not coherent). +// +// If you don't know which sentence is the last one, +// use NMEAorder.ino to list them. You do not have to select +// the last sentence the device sends if you have disabled +// it. Just select the last sentence that you have *enabled*. + +//------------------------------------------------------ +// Enable/Disable coherency: +// +// If you need each fix to contain information that is only +// from the current update interval, you should uncomment +// this define. At the beginning of the next interval, +// the accumulating fix will start out empty. When +// the LAST_SENTENCE_IN_INTERVAL arrives, the valid +// fields will be coherent. + +//#define NMEAGPS_COHERENT + +// With IMPLICIT merging, fix() will be emptied when the +// next sentence begins. +// +// With EXPLICIT or NO merging, the fix() was already +// being initialized. +// +// If you use the fix-oriented methods available() and read(), +// they will empty the current fix for you automatically. +// +// If you use the character-oriented method decode(), you should +// empty the accumulating fix by testing and clearing the +// 'intervalComplete' flag in the same way that available() does. + +//------------------------------------------------------ +// Choose how multiple sentences are merged: +// 1) No merging +// Each sentence fills out its own fix; there could be +// multiple sentences per interval. +// 2) EXPLICIT_MERGING +// All sentences in an interval are *safely* merged into one fix. +// NMEAGPS_FIX_MAX must be >= 1. +// An interval is defined by NMEA_LAST_SENTENCE_IN_INTERVAL. +// 3) IMPLICIT_MERGING +// All sentences in an interval are merged into one fix, with +// possible data loss. If a received sentence is rejected for +// any reason (e.g., a checksum error), all the values are suspect. +// The fix will be cleared; no members will be valid until new +// sentences are received and accepted. This uses less RAM. +// An interval is defined by NMEA_LAST_SENTENCE_IN_INTERVAL. +// Uncomment zero or one: + +#define NMEAGPS_EXPLICIT_MERGING +//#define NMEAGPS_IMPLICIT_MERGING + +#ifdef NMEAGPS_IMPLICIT_MERGING + #define NMEAGPS_MERGING NMEAGPS::IMPLICIT_MERGING + + // When accumulating, nothing is done to the fix at the + // beginning of every sentence... + #ifdef NMEAGPS_COHERENT + // ...unless COHERENT is enabled and a new interval is starting + #define NMEAGPS_INIT_FIX(m) \ + if (intervalComplete()) { intervalComplete( false ); m.valid.init(); } + #else + #define NMEAGPS_INIT_FIX(m) + #endif + + // ...but we invalidate one part when it starts to get parsed. It *may* get + // validated when the parsing is finished. + #define NMEAGPS_INVALIDATE(m) m_fix.valid.m = false + +#else + + #ifdef NMEAGPS_EXPLICIT_MERGING + #define NMEAGPS_MERGING NMEAGPS::EXPLICIT_MERGING + #else + #define NMEAGPS_MERGING NMEAGPS::NO_MERGING + #define NMEAGPS_NO_MERGING + #endif + + // When NOT accumulating, invalidate the entire fix at the + // beginning of every sentence + #define NMEAGPS_INIT_FIX(m) m.valid.init() + + // ...so the individual parts do not need to be invalidated as they are parsed + #define NMEAGPS_INVALIDATE(m) + +#endif + +#if ( defined(NMEAGPS_NO_MERGING) + \ + defined(NMEAGPS_IMPLICIT_MERGING) + \ + defined(NMEAGPS_EXPLICIT_MERGING) ) > 1 + #error Only one MERGING technique should be enabled in NMEAGPS_cfg.h! +#endif + +//------------------------------------------------------ +// Define the fix buffer size. The NMEAGPS object will hold on to +// this many fixes before an overrun occurs. This can be zero, +// but you have to be more careful about using gps.fix() structure, +// because it will be modified as characters are received. + +#define NMEAGPS_FIX_MAX 1 + +#if defined(NMEAGPS_EXPLICIT_MERGING) && (NMEAGPS_FIX_MAX == 0) + #error You must define FIX_MAX >= 1 to allow EXPLICIT merging in NMEAGPS_cfg.h +#endif + +//------------------------------------------------------ +// Enable/Disable interrupt-style processing of GPS characters +// If you are using one of the NeoXXSerial libraries, +// to attachInterrupt, this must be defined. +// Otherwise, it must be commented out. + +//#define NMEAGPS_INTERRUPT_PROCESSING + +#ifdef NMEAGPS_INTERRUPT_PROCESSING + #define NMEAGPS_PROCESSING_STYLE NMEAGPS::PS_INTERRUPT +#else + #define NMEAGPS_PROCESSING_STYLE NMEAGPS::PS_POLLING +#endif + +//------------------------------------------------------ +// Enable/disable the talker ID, manufacturer ID and proprietary message processing. +// +// First, some background information. There are two kinds of NMEA sentences: +// +// 1. Standard NMEA sentences begin with "$ttccc", where +// "tt" is the talker ID, and +// "ccc" is the variable-length sentence type (i.e., command). +// +// For example, "$GPGLL,..." is a GLL sentence (Geographic Lat/Long) +// transmitted by talker "GP". This is the most common talker ID. Some +// devices may report "$GNGLL,..." when a mix of GPS and non-GPS +// satellites have been used to determine the GLL data. +// +// 2. Proprietary NMEA sentences (i.e., those unique to a particular +// manufacturer) begin with "$Pmmmccc", where +// "P" is the NMEA-defined prefix indicator for proprietary messages, +// "mmm" is the 3-character manufacturer ID, and +// "ccc" is the variable-length sentence type (it can be empty). +// +// No validation of manufacturer ID and talker ID is performed in this +// base class. For example, although "GP" is a common talker ID, it is not +// guaranteed to be transmitted by your particular device, and it IS NOT +// REQUIRED. If you need validation of these IDs, or you need to use the +// extra information provided by some devices, you have two independent +// options: +// +// 1. Enable SAVING the ID: When /decode/ returns DECODE_COMPLETED, the +// /talker_id/ and/or /mfr_id/ members will contain ID bytes. The entire +// sentence will be parsed, perhaps modifying members of /fix/. You should +// enable one or both IDs if you want the information in all sentences *and* +// you also want to know the ID bytes. This adds two bytes of RAM for the +// talker ID, and 3 bytes of RAM for the manufacturer ID. +// +// 2. Enable PARSING the ID: The virtual /parse_talker_id/ and +// /parse_mfr_id/ will receive each ID character as it is parsed. If it +// is not a valid ID, return /false/ to abort processing the rest of the +// sentence. No CPU time will be wasted on the invalid sentence, and no +// /fix/ members will be modified. You should enable this if you want to +// ignore some IDs. You must override /parse_talker_id/ and/or +// /parse_mfr_id/ in a derived class. +// + +//#define NMEAGPS_SAVE_TALKER_ID +//#define NMEAGPS_PARSE_TALKER_ID + +//#define NMEAGPS_PARSE_PROPRIETARY +#ifdef NMEAGPS_PARSE_PROPRIETARY + //#define NMEAGPS_SAVE_MFR_ID + #define NMEAGPS_PARSE_MFR_ID +#endif + +//------------------------------------------------------ +// Enable/disable tracking the current satellite array and, +// optionally, all the info for each satellite. +// + +#define NMEAGPS_PARSE_SATELLITES +#define NMEAGPS_PARSE_SATELLITE_INFO + +#ifdef NMEAGPS_PARSE_SATELLITES + #define NMEAGPS_MAX_SATELLITES (20) + + #ifndef GPS_FIX_SATELLITES + #error GPS_FIX_SATELLITES must be defined in GPSfix.h! + #endif + +#endif + +#if defined(NMEAGPS_PARSE_SATELLITE_INFO) & \ + !defined(NMEAGPS_PARSE_SATELLITES) + #error NMEAGPS_PARSE_SATELLITES must be defined! +#endif + +//------------------------------------------------------ +// Enable/disable gathering interface statistics: +// CRC errors and number of sentences received + +#define NMEAGPS_STATS + +//------------------------------------------------------ +// Configuration item for allowing derived types of NMEAGPS. +// If you derive classes from NMEAGPS, you *must* define NMEAGPS_DERIVED_TYPES. +// If not defined, virtuals are not used, with a slight size (2 bytes) and +// execution time savings. + +//#define NMEAGPS_DERIVED_TYPES + +#ifdef NMEAGPS_DERIVED_TYPES + #define NMEAGPS_VIRTUAL virtual +#else + #define NMEAGPS_VIRTUAL +#endif + +//----------------------------------- +// See if DERIVED_TYPES is required +#if (defined(NMEAGPS_PARSE_TALKER_ID) | defined(NMEAGPS_PARSE_MFR_ID)) & \ + !defined(NMEAGPS_DERIVED_TYPES) + #error You must define NMEAGPS_DERIVED_TYPES in NMEAGPS.h in order to parse Talker and/or Mfr IDs! +#endif + +//------------------------------------------------------ +// Some devices may omit trailing commas at the end of some +// sentences. This may prevent the last field from being +// parsed correctly, because the parser for some types keep +// the value in an intermediate state until the complete +// field is received (e.g., parseDDDMM, parseFloat and +// parseZDA). +// +// Enabling this will inject a simulated comma when the end +// of a sentence is received and the last field parser +// indicated that it still needs one. + +//#define NMEAGPS_COMMA_NEEDED + +//------------------------------------------------------ +// Some applications may want to recognize a sentence type +// without actually parsing any of the fields. Uncommenting +// this define will allow the nmeaMessage member to be set +// when *any* standard message is seen, even though that +// message is not enabled by a NMEAGPS_PARSE_xxx define above. +// No valid flags will be true for those sentences. + +#define NMEAGPS_RECOGNIZE_ALL + +//------------------------------------------------------ +// Sometimes, a little extra space is needed to parse an intermediate form. +// This config items enables extra space. + +#define NMEAGPS_PARSING_SCRATCHPAD + +#endif \ No newline at end of file diff --git a/software/firmware/libraries/NeoGPS/extras/configs/Full/NeoGPS_cfg.h b/software/firmware/libraries/NeoGPS/extras/configs/Full/NeoGPS_cfg.h new file mode 100644 index 0000000..7ad6b70 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/configs/Full/NeoGPS_cfg.h @@ -0,0 +1,85 @@ +#ifndef NEOGPS_CFG +#define NEOGPS_CFG + +/** + * Enable/disable packed data structures. + * + * Enabling packed data structures will use two less-portable language + * features of GCC to reduce RAM requirements. Although it was expected to slightly increase execution time and code size, the reverse is true on 8-bit AVRs: the code is smaller and faster with packing enabled. + * + * Disabling packed data structures will be very portable to other + * platforms. NeoGPS configurations will use slightly more RAM, and on + * 8-bit AVRs, the speed is slightly slower, and the code is slightly + * larger. There may be no choice but to disable packing on processors + * that do not support packed structures. + * + * There may also be compiler-specific switches that affect packing and the + * code which accesses packed members. YMMV. + **/ + +#ifdef __AVR__ + #define NEOGPS_PACKED_DATA +#endif + +//------------------------------------------------------------------------ +// Based on the above define, choose which set of packing macros should +// be used in the rest of the NeoGPS package. Do not change these defines. + +#ifdef NEOGPS_PACKED_DATA + + // This is for specifying the number of bits to be used for a + // member of a struct. Booleans are typically one bit. + #define NEOGPS_BF(b) :b + + // This is for requesting the compiler to pack the struct or class members + // "as closely as possible". This is a compiler-dependent interpretation. + #define NEOGPS_PACKED __attribute__((packed)) + +#else + + // Let the compiler do whatever it wants. + + #define NEOGPS_PACKED + #define NEOGPS_BF(b) + +#endif + +/* + * Accommodate C++ compiler and IDE changes. + * + * Declaring constants as class data instead of instance data helps avoid + * collisions with #define names, and allows the compiler to perform more + * checks on their usage. + * + * Until C++ 10 and IDE 1.6.8, initialized class data constants + * were declared like this: + * + * static const = ; + * + * Now, non-simple types (e.g., float) must be declared as + * + * static constexpr = ; + * + * The good news is that this allows the compiler to optimize out an + * expression that is "promised" to be "evaluatable" as a constant. + * The bad news is that it introduces a new language keyword, and the old + * code raises an error. + * + * TODO: Evaluate the requirement for the "static" keyword. + * TODO: Evaluate using a C++ version preprocessor symbol for the #if. + * + * The CONST_CLASS_DATA define will expand to the appropriate keywords. + * + */ + +#if ARDUINO < 10606 + + #define CONST_CLASS_DATA static const + +#else + + #define CONST_CLASS_DATA static constexpr + +#endif + +#endif diff --git a/software/firmware/libraries/NeoGPS/extras/configs/Minimal/GPSfix_cfg.h b/software/firmware/libraries/NeoGPS/extras/configs/Minimal/GPSfix_cfg.h new file mode 100644 index 0000000..5cdaa00 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/configs/Minimal/GPSfix_cfg.h @@ -0,0 +1,35 @@ +#ifndef GPS_FIX_CFG +#define GPS_FIX_CFG + +/** + * Enable/disable the storage for the members of a fix. + * + * Disabling a member prevents it from being parsed from a received message. + * The disabled member cannot be accessed or stored, and its validity flag + * would not be available. It will not be declared, and code that uses that + * member will not compile. + * + * DATE and TIME are somewhat coupled in that they share a single `time_t`, + * but they have separate validity flags. + * + * See also note regarding the DOP members, below. + * + */ + +//#define GPS_FIX_DATE +//#define GPS_FIX_TIME +//#define GPS_FIX_LOCATION +//#define GPS_FIX_LOCATION_DMS +//#define GPS_FIX_ALTITUDE +//#define GPS_FIX_SPEED +//#define GPS_FIX_HEADING +//#define GPS_FIX_SATELLITES +//#define GPS_FIX_HDOP +//#define GPS_FIX_VDOP +//#define GPS_FIX_PDOP +//#define GPS_FIX_LAT_ERR +//#define GPS_FIX_LON_ERR +//#define GPS_FIX_ALT_ERR +//#define GPS_FIX_GEOID_HEIGHT + +#endif diff --git a/software/firmware/libraries/NeoGPS/extras/configs/Minimal/NMEAGPS_cfg.h b/software/firmware/libraries/NeoGPS/extras/configs/Minimal/NMEAGPS_cfg.h new file mode 100644 index 0000000..a41564c --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/configs/Minimal/NMEAGPS_cfg.h @@ -0,0 +1,286 @@ +#ifndef NMEAGPS_CFG_H +#define NMEAGPS_CFG_H + +//------------------------------------------------------ +// Enable/disable the parsing of specific sentences. +// +// Configuring out a sentence prevents it from being recognized; it +// will be completely ignored. (See also NMEAGPS_RECOGNIZE_ALL, below) +// +// FYI: Only RMC and ZDA contain date information. Other +// sentences contain time information. Both date and time are +// required if you will be doing time_t-to-clock_t operations. + +//#define NMEAGPS_PARSE_GGA +//#define NMEAGPS_PARSE_GLL +//#define NMEAGPS_PARSE_GSA +//#define NMEAGPS_PARSE_GSV +//#define NMEAGPS_PARSE_GST +#define NMEAGPS_PARSE_RMC +//#define NMEAGPS_PARSE_VTG +//#define NMEAGPS_PARSE_ZDA + +//------------------------------------------------------ +// Select which sentence is sent *last* by your GPS device +// in each update interval. This can be used by your sketch +// to determine when the GPS quiet time begins, and thus +// when you can perform "some" time-consuming operations. + +#define LAST_SENTENCE_IN_INTERVAL NMEAGPS::NMEA_RMC + +// If the NMEA_LAST_SENTENCE_IN_INTERVAL is not chosen +// correctly, GPS data may be lost because the sketch +// takes too long elsewhere when this sentence is received. +// Also, fix members may contain information from different +// time intervals (i.e., they are not coherent). +// +// If you don't know which sentence is the last one, +// use NMEAorder.ino to list them. You do not have to select +// the last sentence the device sends if you have disabled +// it. Just select the last sentence that you have *enabled*. + +//------------------------------------------------------ +// Enable/Disable coherency: +// +// If you need each fix to contain information that is only +// from the current update interval, you should uncomment +// this define. At the beginning of the next interval, +// the accumulating fix will start out empty. When +// the LAST_SENTENCE_IN_INTERVAL arrives, the valid +// fields will be coherent. + +//#define NMEAGPS_COHERENT + +// With IMPLICIT merging, fix() will be emptied when the +// next sentence begins. +// +// With EXPLICIT or NO merging, the fix() was already +// being initialized. +// +// If you use the fix-oriented methods available() and read(), +// they will empty the current fix for you automatically. +// +// If you use the character-oriented method decode(), you should +// empty the accumulating fix by testing and clearing the +// 'intervalComplete' flag in the same way that available() does. + +//------------------------------------------------------ +// Choose how multiple sentences are merged: +// 1) No merging +// Each sentence fills out its own fix; there could be +// multiple sentences per interval. +// 2) EXPLICIT_MERGING +// All sentences in an interval are *safely* merged into one fix. +// NMEAGPS_FIX_MAX must be >= 1. +// An interval is defined by NMEA_LAST_SENTENCE_IN_INTERVAL. +// 3) IMPLICIT_MERGING +// All sentences in an interval are merged into one fix, with +// possible data loss. If a received sentence is rejected for +// any reason (e.g., a checksum error), all the values are suspect. +// The fix will be cleared; no members will be valid until new +// sentences are received and accepted. This uses less RAM. +// An interval is defined by NMEA_LAST_SENTENCE_IN_INTERVAL. +// Uncomment zero or one: + +#define NMEAGPS_EXPLICIT_MERGING +//#define NMEAGPS_IMPLICIT_MERGING + +#ifdef NMEAGPS_IMPLICIT_MERGING + #define NMEAGPS_MERGING NMEAGPS::IMPLICIT_MERGING + + // When accumulating, nothing is done to the fix at the + // beginning of every sentence... + #ifdef NMEAGPS_COHERENT + // ...unless COHERENT is enabled and a new interval is starting + #define NMEAGPS_INIT_FIX(m) \ + if (intervalComplete()) { intervalComplete( false ); m.valid.init(); } + #else + #define NMEAGPS_INIT_FIX(m) + #endif + + // ...but we invalidate one part when it starts to get parsed. It *may* get + // validated when the parsing is finished. + #define NMEAGPS_INVALIDATE(m) m_fix.valid.m = false + +#else + + #ifdef NMEAGPS_EXPLICIT_MERGING + #define NMEAGPS_MERGING NMEAGPS::EXPLICIT_MERGING + #else + #define NMEAGPS_MERGING NMEAGPS::NO_MERGING + #define NMEAGPS_NO_MERGING + #endif + + // When NOT accumulating, invalidate the entire fix at the + // beginning of every sentence + #define NMEAGPS_INIT_FIX(m) m.valid.init() + + // ...so the individual parts do not need to be invalidated as they are parsed + #define NMEAGPS_INVALIDATE(m) + +#endif + +#if ( defined(NMEAGPS_NO_MERGING) + \ + defined(NMEAGPS_IMPLICIT_MERGING) + \ + defined(NMEAGPS_EXPLICIT_MERGING) ) > 1 + #error Only one MERGING technique should be enabled in NMEAGPS_cfg.h! +#endif + +//------------------------------------------------------ +// Define the fix buffer size. The NMEAGPS object will hold on to +// this many fixes before an overrun occurs. This can be zero, +// but you have to be more careful about using gps.fix() structure, +// because it will be modified as characters are received. + +#define NMEAGPS_FIX_MAX 1 + +#if defined(NMEAGPS_EXPLICIT_MERGING) && (NMEAGPS_FIX_MAX == 0) + #error You must define FIX_MAX >= 1 to allow EXPLICIT merging in NMEAGPS_cfg.h +#endif + +//------------------------------------------------------ +// Enable/Disable interrupt-style processing of GPS characters +// If you are using one of the NeoXXSerial libraries, +// to attachInterrupt, this must be defined. +// Otherwise, it must be commented out. + +//#define NMEAGPS_INTERRUPT_PROCESSING + +#ifdef NMEAGPS_INTERRUPT_PROCESSING + #define NMEAGPS_PROCESSING_STYLE NMEAGPS::PS_INTERRUPT +#else + #define NMEAGPS_PROCESSING_STYLE NMEAGPS::PS_POLLING +#endif + +//------------------------------------------------------ +// Enable/disable the talker ID, manufacturer ID and proprietary message processing. +// +// First, some background information. There are two kinds of NMEA sentences: +// +// 1. Standard NMEA sentences begin with "$ttccc", where +// "tt" is the talker ID, and +// "ccc" is the variable-length sentence type (i.e., command). +// +// For example, "$GPGLL,..." is a GLL sentence (Geographic Lat/Long) +// transmitted by talker "GP". This is the most common talker ID. Some +// devices may report "$GNGLL,..." when a mix of GPS and non-GPS +// satellites have been used to determine the GLL data. +// +// 2. Proprietary NMEA sentences (i.e., those unique to a particular +// manufacturer) begin with "$Pmmmccc", where +// "P" is the NMEA-defined prefix indicator for proprietary messages, +// "mmm" is the 3-character manufacturer ID, and +// "ccc" is the variable-length sentence type (it can be empty). +// +// No validation of manufacturer ID and talker ID is performed in this +// base class. For example, although "GP" is a common talker ID, it is not +// guaranteed to be transmitted by your particular device, and it IS NOT +// REQUIRED. If you need validation of these IDs, or you need to use the +// extra information provided by some devices, you have two independent +// options: +// +// 1. Enable SAVING the ID: When /decode/ returns DECODE_COMPLETED, the +// /talker_id/ and/or /mfr_id/ members will contain ID bytes. The entire +// sentence will be parsed, perhaps modifying members of /fix/. You should +// enable one or both IDs if you want the information in all sentences *and* +// you also want to know the ID bytes. This adds two bytes of RAM for the +// talker ID, and 3 bytes of RAM for the manufacturer ID. +// +// 2. Enable PARSING the ID: The virtual /parse_talker_id/ and +// /parse_mfr_id/ will receive each ID character as it is parsed. If it +// is not a valid ID, return /false/ to abort processing the rest of the +// sentence. No CPU time will be wasted on the invalid sentence, and no +// /fix/ members will be modified. You should enable this if you want to +// ignore some IDs. You must override /parse_talker_id/ and/or +// /parse_mfr_id/ in a derived class. +// + +//#define NMEAGPS_SAVE_TALKER_ID +//#define NMEAGPS_PARSE_TALKER_ID + +//#define NMEAGPS_PARSE_PROPRIETARY +#ifdef NMEAGPS_PARSE_PROPRIETARY + //#define NMEAGPS_SAVE_MFR_ID + #define NMEAGPS_PARSE_MFR_ID +#endif + +//------------------------------------------------------ +// Enable/disable tracking the current satellite array and, +// optionally, all the info for each satellite. +// + +//#define NMEAGPS_PARSE_SATELLITES +//#define NMEAGPS_PARSE_SATELLITE_INFO + +#ifdef NMEAGPS_PARSE_SATELLITES + #define NMEAGPS_MAX_SATELLITES (20) + + #ifndef GPS_FIX_SATELLITES + #error GPS_FIX_SATELLITES must be defined in GPSfix.h! + #endif + +#endif + +#if defined(NMEAGPS_PARSE_SATELLITE_INFO) & \ + !defined(NMEAGPS_PARSE_SATELLITES) + #error NMEAGPS_PARSE_SATELLITES must be defined! +#endif + +//------------------------------------------------------ +// Enable/disable gathering interface statistics: +// CRC errors and number of sentences received + +//#define NMEAGPS_STATS + +//------------------------------------------------------ +// Configuration item for allowing derived types of NMEAGPS. +// If you derive classes from NMEAGPS, you *must* define NMEAGPS_DERIVED_TYPES. +// If not defined, virtuals are not used, with a slight size (2 bytes) and +// execution time savings. + +//#define NMEAGPS_DERIVED_TYPES + +#ifdef NMEAGPS_DERIVED_TYPES + #define NMEAGPS_VIRTUAL virtual +#else + #define NMEAGPS_VIRTUAL +#endif + +//----------------------------------- +// See if DERIVED_TYPES is required +#if (defined(NMEAGPS_PARSE_TALKER_ID) | defined(NMEAGPS_PARSE_MFR_ID)) & \ + !defined(NMEAGPS_DERIVED_TYPES) + #error You must define NMEAGPS_DERIVED_TYPES in NMEAGPS.h in order to parse Talker and/or Mfr IDs! +#endif + +//------------------------------------------------------ +// Some devices may omit trailing commas at the end of some +// sentences. This may prevent the last field from being +// parsed correctly, because the parser for some types keep +// the value in an intermediate state until the complete +// field is received (e.g., parseDDDMM, parseFloat and +// parseZDA). +// +// Enabling this will inject a simulated comma when the end +// of a sentence is received and the last field parser +// indicated that it still needs one. + +//#define NMEAGPS_COMMA_NEEDED + +//------------------------------------------------------ +// Some applications may want to recognize a sentence type +// without actually parsing any of the fields. Uncommenting +// this define will allow the nmeaMessage member to be set +// when *any* standard message is seen, even though that +// message is not enabled by a NMEAGPS_PARSE_xxx define above. +// No valid flags will be true for those sentences. + +//#define NMEAGPS_RECOGNIZE_ALL + +//------------------------------------------------------ +// Sometimes, a little extra space is needed to parse an intermediate form. +// This config items enables extra space. + +//#define NMEAGPS_PARSING_SCRATCHPAD + +#endif \ No newline at end of file diff --git a/software/firmware/libraries/NeoGPS/extras/configs/Minimal/NeoGPS_cfg.h b/software/firmware/libraries/NeoGPS/extras/configs/Minimal/NeoGPS_cfg.h new file mode 100644 index 0000000..7ad6b70 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/configs/Minimal/NeoGPS_cfg.h @@ -0,0 +1,85 @@ +#ifndef NEOGPS_CFG +#define NEOGPS_CFG + +/** + * Enable/disable packed data structures. + * + * Enabling packed data structures will use two less-portable language + * features of GCC to reduce RAM requirements. Although it was expected to slightly increase execution time and code size, the reverse is true on 8-bit AVRs: the code is smaller and faster with packing enabled. + * + * Disabling packed data structures will be very portable to other + * platforms. NeoGPS configurations will use slightly more RAM, and on + * 8-bit AVRs, the speed is slightly slower, and the code is slightly + * larger. There may be no choice but to disable packing on processors + * that do not support packed structures. + * + * There may also be compiler-specific switches that affect packing and the + * code which accesses packed members. YMMV. + **/ + +#ifdef __AVR__ + #define NEOGPS_PACKED_DATA +#endif + +//------------------------------------------------------------------------ +// Based on the above define, choose which set of packing macros should +// be used in the rest of the NeoGPS package. Do not change these defines. + +#ifdef NEOGPS_PACKED_DATA + + // This is for specifying the number of bits to be used for a + // member of a struct. Booleans are typically one bit. + #define NEOGPS_BF(b) :b + + // This is for requesting the compiler to pack the struct or class members + // "as closely as possible". This is a compiler-dependent interpretation. + #define NEOGPS_PACKED __attribute__((packed)) + +#else + + // Let the compiler do whatever it wants. + + #define NEOGPS_PACKED + #define NEOGPS_BF(b) + +#endif + +/* + * Accommodate C++ compiler and IDE changes. + * + * Declaring constants as class data instead of instance data helps avoid + * collisions with #define names, and allows the compiler to perform more + * checks on their usage. + * + * Until C++ 10 and IDE 1.6.8, initialized class data constants + * were declared like this: + * + * static const = ; + * + * Now, non-simple types (e.g., float) must be declared as + * + * static constexpr = ; + * + * The good news is that this allows the compiler to optimize out an + * expression that is "promised" to be "evaluatable" as a constant. + * The bad news is that it introduces a new language keyword, and the old + * code raises an error. + * + * TODO: Evaluate the requirement for the "static" keyword. + * TODO: Evaluate using a C++ version preprocessor symbol for the #if. + * + * The CONST_CLASS_DATA define will expand to the appropriate keywords. + * + */ + +#if ARDUINO < 10606 + + #define CONST_CLASS_DATA static const + +#else + + #define CONST_CLASS_DATA static constexpr + +#endif + +#endif diff --git a/software/firmware/libraries/NeoGPS/extras/configs/Nominal/GPSfix_cfg.h b/software/firmware/libraries/NeoGPS/extras/configs/Nominal/GPSfix_cfg.h new file mode 100644 index 0000000..979b41a --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/configs/Nominal/GPSfix_cfg.h @@ -0,0 +1,35 @@ +#ifndef GPS_FIX_CFG +#define GPS_FIX_CFG + +/** + * Enable/disable the storage for the members of a fix. + * + * Disabling a member prevents it from being parsed from a received message. + * The disabled member cannot be accessed or stored, and its validity flag + * would not be available. It will not be declared, and code that uses that + * member will not compile. + * + * DATE and TIME are somewhat coupled in that they share a single `time_t`, + * but they have separate validity flags. + * + * See also note regarding the DOP members, below. + * + */ + +#define GPS_FIX_DATE +#define GPS_FIX_TIME +#define GPS_FIX_LOCATION +//#define GPS_FIX_LOCATION_DMS +#define GPS_FIX_ALTITUDE +#define GPS_FIX_SPEED +#define GPS_FIX_HEADING +#define GPS_FIX_SATELLITES +//#define GPS_FIX_HDOP +//#define GPS_FIX_VDOP +//#define GPS_FIX_PDOP +//#define GPS_FIX_LAT_ERR +//#define GPS_FIX_LON_ERR +//#define GPS_FIX_ALT_ERR +//#define GPS_FIX_GEOID_HEIGHT + +#endif diff --git a/software/firmware/libraries/NeoGPS/extras/configs/Nominal/NMEAGPS_cfg.h b/software/firmware/libraries/NeoGPS/extras/configs/Nominal/NMEAGPS_cfg.h new file mode 100644 index 0000000..3172d20 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/configs/Nominal/NMEAGPS_cfg.h @@ -0,0 +1,286 @@ +#ifndef NMEAGPS_CFG_H +#define NMEAGPS_CFG_H + +//------------------------------------------------------ +// Enable/disable the parsing of specific sentences. +// +// Configuring out a sentence prevents it from being recognized; it +// will be completely ignored. (See also NMEAGPS_RECOGNIZE_ALL, below) +// +// FYI: Only RMC and ZDA contain date information. Other +// sentences contain time information. Both date and time are +// required if you will be doing time_t-to-clock_t operations. + +#define NMEAGPS_PARSE_GGA +//#define NMEAGPS_PARSE_GLL +//#define NMEAGPS_PARSE_GSA +//#define NMEAGPS_PARSE_GSV +//#define NMEAGPS_PARSE_GST +#define NMEAGPS_PARSE_RMC +//#define NMEAGPS_PARSE_VTG +//#define NMEAGPS_PARSE_ZDA + +//------------------------------------------------------ +// Select which sentence is sent *last* by your GPS device +// in each update interval. This can be used by your sketch +// to determine when the GPS quiet time begins, and thus +// when you can perform "some" time-consuming operations. + +#define LAST_SENTENCE_IN_INTERVAL NMEAGPS::NMEA_RMC + +// If the NMEA_LAST_SENTENCE_IN_INTERVAL is not chosen +// correctly, GPS data may be lost because the sketch +// takes too long elsewhere when this sentence is received. +// Also, fix members may contain information from different +// time intervals (i.e., they are not coherent). +// +// If you don't know which sentence is the last one, +// use NMEAorder.ino to list them. You do not have to select +// the last sentence the device sends if you have disabled +// it. Just select the last sentence that you have *enabled*. + +//------------------------------------------------------ +// Enable/Disable coherency: +// +// If you need each fix to contain information that is only +// from the current update interval, you should uncomment +// this define. At the beginning of the next interval, +// the accumulating fix will start out empty. When +// the LAST_SENTENCE_IN_INTERVAL arrives, the valid +// fields will be coherent. + +//#define NMEAGPS_COHERENT + +// With IMPLICIT merging, fix() will be emptied when the +// next sentence begins. +// +// With EXPLICIT or NO merging, the fix() was already +// being initialized. +// +// If you use the fix-oriented methods available() and read(), +// they will empty the current fix for you automatically. +// +// If you use the character-oriented method decode(), you should +// empty the accumulating fix by testing and clearing the +// 'intervalComplete' flag in the same way that available() does. + +//------------------------------------------------------ +// Choose how multiple sentences are merged: +// 1) No merging +// Each sentence fills out its own fix; there could be +// multiple sentences per interval. +// 2) EXPLICIT_MERGING +// All sentences in an interval are *safely* merged into one fix. +// NMEAGPS_FIX_MAX must be >= 1. +// An interval is defined by NMEA_LAST_SENTENCE_IN_INTERVAL. +// 3) IMPLICIT_MERGING +// All sentences in an interval are merged into one fix, with +// possible data loss. If a received sentence is rejected for +// any reason (e.g., a checksum error), all the values are suspect. +// The fix will be cleared; no members will be valid until new +// sentences are received and accepted. This uses less RAM. +// An interval is defined by NMEA_LAST_SENTENCE_IN_INTERVAL. +// Uncomment zero or one: + +#define NMEAGPS_EXPLICIT_MERGING +//#define NMEAGPS_IMPLICIT_MERGING + +#ifdef NMEAGPS_IMPLICIT_MERGING + #define NMEAGPS_MERGING NMEAGPS::IMPLICIT_MERGING + + // When accumulating, nothing is done to the fix at the + // beginning of every sentence... + #ifdef NMEAGPS_COHERENT + // ...unless COHERENT is enabled and a new interval is starting + #define NMEAGPS_INIT_FIX(m) \ + if (intervalComplete()) { intervalComplete( false ); m.valid.init(); } + #else + #define NMEAGPS_INIT_FIX(m) + #endif + + // ...but we invalidate one part when it starts to get parsed. It *may* get + // validated when the parsing is finished. + #define NMEAGPS_INVALIDATE(m) m_fix.valid.m = false + +#else + + #ifdef NMEAGPS_EXPLICIT_MERGING + #define NMEAGPS_MERGING NMEAGPS::EXPLICIT_MERGING + #else + #define NMEAGPS_MERGING NMEAGPS::NO_MERGING + #define NMEAGPS_NO_MERGING + #endif + + // When NOT accumulating, invalidate the entire fix at the + // beginning of every sentence + #define NMEAGPS_INIT_FIX(m) m.valid.init() + + // ...so the individual parts do not need to be invalidated as they are parsed + #define NMEAGPS_INVALIDATE(m) + +#endif + +#if ( defined(NMEAGPS_NO_MERGING) + \ + defined(NMEAGPS_IMPLICIT_MERGING) + \ + defined(NMEAGPS_EXPLICIT_MERGING) ) > 1 + #error Only one MERGING technique should be enabled in NMEAGPS_cfg.h! +#endif + +//------------------------------------------------------ +// Define the fix buffer size. The NMEAGPS object will hold on to +// this many fixes before an overrun occurs. This can be zero, +// but you have to be more careful about using gps.fix() structure, +// because it will be modified as characters are received. + +#define NMEAGPS_FIX_MAX 1 + +#if defined(NMEAGPS_EXPLICIT_MERGING) && (NMEAGPS_FIX_MAX == 0) + #error You must define FIX_MAX >= 1 to allow EXPLICIT merging in NMEAGPS_cfg.h +#endif + +//------------------------------------------------------ +// Enable/Disable interrupt-style processing of GPS characters +// If you are using one of the NeoXXSerial libraries, +// to attachInterrupt, this must be defined. +// Otherwise, it must be commented out. + +//#define NMEAGPS_INTERRUPT_PROCESSING + +#ifdef NMEAGPS_INTERRUPT_PROCESSING + #define NMEAGPS_PROCESSING_STYLE NMEAGPS::PS_INTERRUPT +#else + #define NMEAGPS_PROCESSING_STYLE NMEAGPS::PS_POLLING +#endif + +//------------------------------------------------------ +// Enable/disable the talker ID, manufacturer ID and proprietary message processing. +// +// First, some background information. There are two kinds of NMEA sentences: +// +// 1. Standard NMEA sentences begin with "$ttccc", where +// "tt" is the talker ID, and +// "ccc" is the variable-length sentence type (i.e., command). +// +// For example, "$GPGLL,..." is a GLL sentence (Geographic Lat/Long) +// transmitted by talker "GP". This is the most common talker ID. Some +// devices may report "$GNGLL,..." when a mix of GPS and non-GPS +// satellites have been used to determine the GLL data. +// +// 2. Proprietary NMEA sentences (i.e., those unique to a particular +// manufacturer) begin with "$Pmmmccc", where +// "P" is the NMEA-defined prefix indicator for proprietary messages, +// "mmm" is the 3-character manufacturer ID, and +// "ccc" is the variable-length sentence type (it can be empty). +// +// No validation of manufacturer ID and talker ID is performed in this +// base class. For example, although "GP" is a common talker ID, it is not +// guaranteed to be transmitted by your particular device, and it IS NOT +// REQUIRED. If you need validation of these IDs, or you need to use the +// extra information provided by some devices, you have two independent +// options: +// +// 1. Enable SAVING the ID: When /decode/ returns DECODE_COMPLETED, the +// /talker_id/ and/or /mfr_id/ members will contain ID bytes. The entire +// sentence will be parsed, perhaps modifying members of /fix/. You should +// enable one or both IDs if you want the information in all sentences *and* +// you also want to know the ID bytes. This adds two bytes of RAM for the +// talker ID, and 3 bytes of RAM for the manufacturer ID. +// +// 2. Enable PARSING the ID: The virtual /parse_talker_id/ and +// /parse_mfr_id/ will receive each ID character as it is parsed. If it +// is not a valid ID, return /false/ to abort processing the rest of the +// sentence. No CPU time will be wasted on the invalid sentence, and no +// /fix/ members will be modified. You should enable this if you want to +// ignore some IDs. You must override /parse_talker_id/ and/or +// /parse_mfr_id/ in a derived class. +// + +//#define NMEAGPS_SAVE_TALKER_ID +//#define NMEAGPS_PARSE_TALKER_ID + +//#define NMEAGPS_PARSE_PROPRIETARY +#ifdef NMEAGPS_PARSE_PROPRIETARY + //#define NMEAGPS_SAVE_MFR_ID + #define NMEAGPS_PARSE_MFR_ID +#endif + +//------------------------------------------------------ +// Enable/disable tracking the current satellite array and, +// optionally, all the info for each satellite. +// + +//#define NMEAGPS_PARSE_SATELLITES +//#define NMEAGPS_PARSE_SATELLITE_INFO + +#ifdef NMEAGPS_PARSE_SATELLITES + #define NMEAGPS_MAX_SATELLITES (20) + + #ifndef GPS_FIX_SATELLITES + #error GPS_FIX_SATELLITES must be defined in GPSfix.h! + #endif + +#endif + +#if defined(NMEAGPS_PARSE_SATELLITE_INFO) & \ + !defined(NMEAGPS_PARSE_SATELLITES) + #error NMEAGPS_PARSE_SATELLITES must be defined! +#endif + +//------------------------------------------------------ +// Enable/disable gathering interface statistics: +// CRC errors and number of sentences received + +#define NMEAGPS_STATS + +//------------------------------------------------------ +// Configuration item for allowing derived types of NMEAGPS. +// If you derive classes from NMEAGPS, you *must* define NMEAGPS_DERIVED_TYPES. +// If not defined, virtuals are not used, with a slight size (2 bytes) and +// execution time savings. + +//#define NMEAGPS_DERIVED_TYPES + +#ifdef NMEAGPS_DERIVED_TYPES + #define NMEAGPS_VIRTUAL virtual +#else + #define NMEAGPS_VIRTUAL +#endif + +//----------------------------------- +// See if DERIVED_TYPES is required +#if (defined(NMEAGPS_PARSE_TALKER_ID) | defined(NMEAGPS_PARSE_MFR_ID)) & \ + !defined(NMEAGPS_DERIVED_TYPES) + #error You must define NMEAGPS_DERIVED_TYPES in NMEAGPS.h in order to parse Talker and/or Mfr IDs! +#endif + +//------------------------------------------------------ +// Some devices may omit trailing commas at the end of some +// sentences. This may prevent the last field from being +// parsed correctly, because the parser for some types keep +// the value in an intermediate state until the complete +// field is received (e.g., parseDDDMM, parseFloat and +// parseZDA). +// +// Enabling this will inject a simulated comma when the end +// of a sentence is received and the last field parser +// indicated that it still needs one. + +//#define NMEAGPS_COMMA_NEEDED + +//------------------------------------------------------ +// Some applications may want to recognize a sentence type +// without actually parsing any of the fields. Uncommenting +// this define will allow the nmeaMessage member to be set +// when *any* standard message is seen, even though that +// message is not enabled by a NMEAGPS_PARSE_xxx define above. +// No valid flags will be true for those sentences. + +#define NMEAGPS_RECOGNIZE_ALL + +//------------------------------------------------------ +// Sometimes, a little extra space is needed to parse an intermediate form. +// This config items enables extra space. + +//#define NMEAGPS_PARSING_SCRATCHPAD + +#endif \ No newline at end of file diff --git a/software/firmware/libraries/NeoGPS/extras/configs/Nominal/NeoGPS_cfg.h b/software/firmware/libraries/NeoGPS/extras/configs/Nominal/NeoGPS_cfg.h new file mode 100644 index 0000000..7ad6b70 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/configs/Nominal/NeoGPS_cfg.h @@ -0,0 +1,85 @@ +#ifndef NEOGPS_CFG +#define NEOGPS_CFG + +/** + * Enable/disable packed data structures. + * + * Enabling packed data structures will use two less-portable language + * features of GCC to reduce RAM requirements. Although it was expected to slightly increase execution time and code size, the reverse is true on 8-bit AVRs: the code is smaller and faster with packing enabled. + * + * Disabling packed data structures will be very portable to other + * platforms. NeoGPS configurations will use slightly more RAM, and on + * 8-bit AVRs, the speed is slightly slower, and the code is slightly + * larger. There may be no choice but to disable packing on processors + * that do not support packed structures. + * + * There may also be compiler-specific switches that affect packing and the + * code which accesses packed members. YMMV. + **/ + +#ifdef __AVR__ + #define NEOGPS_PACKED_DATA +#endif + +//------------------------------------------------------------------------ +// Based on the above define, choose which set of packing macros should +// be used in the rest of the NeoGPS package. Do not change these defines. + +#ifdef NEOGPS_PACKED_DATA + + // This is for specifying the number of bits to be used for a + // member of a struct. Booleans are typically one bit. + #define NEOGPS_BF(b) :b + + // This is for requesting the compiler to pack the struct or class members + // "as closely as possible". This is a compiler-dependent interpretation. + #define NEOGPS_PACKED __attribute__((packed)) + +#else + + // Let the compiler do whatever it wants. + + #define NEOGPS_PACKED + #define NEOGPS_BF(b) + +#endif + +/* + * Accommodate C++ compiler and IDE changes. + * + * Declaring constants as class data instead of instance data helps avoid + * collisions with #define names, and allows the compiler to perform more + * checks on their usage. + * + * Until C++ 10 and IDE 1.6.8, initialized class data constants + * were declared like this: + * + * static const = ; + * + * Now, non-simple types (e.g., float) must be declared as + * + * static constexpr = ; + * + * The good news is that this allows the compiler to optimize out an + * expression that is "promised" to be "evaluatable" as a constant. + * The bad news is that it introduces a new language keyword, and the old + * code raises an error. + * + * TODO: Evaluate the requirement for the "static" keyword. + * TODO: Evaluate using a C++ version preprocessor symbol for the #if. + * + * The CONST_CLASS_DATA define will expand to the appropriate keywords. + * + */ + +#if ARDUINO < 10606 + + #define CONST_CLASS_DATA static const + +#else + + #define CONST_CLASS_DATA static constexpr + +#endif + +#endif diff --git a/software/firmware/libraries/NeoGPS/extras/configs/PUBX/GPSfix_cfg.h b/software/firmware/libraries/NeoGPS/extras/configs/PUBX/GPSfix_cfg.h new file mode 100644 index 0000000..979b41a --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/configs/PUBX/GPSfix_cfg.h @@ -0,0 +1,35 @@ +#ifndef GPS_FIX_CFG +#define GPS_FIX_CFG + +/** + * Enable/disable the storage for the members of a fix. + * + * Disabling a member prevents it from being parsed from a received message. + * The disabled member cannot be accessed or stored, and its validity flag + * would not be available. It will not be declared, and code that uses that + * member will not compile. + * + * DATE and TIME are somewhat coupled in that they share a single `time_t`, + * but they have separate validity flags. + * + * See also note regarding the DOP members, below. + * + */ + +#define GPS_FIX_DATE +#define GPS_FIX_TIME +#define GPS_FIX_LOCATION +//#define GPS_FIX_LOCATION_DMS +#define GPS_FIX_ALTITUDE +#define GPS_FIX_SPEED +#define GPS_FIX_HEADING +#define GPS_FIX_SATELLITES +//#define GPS_FIX_HDOP +//#define GPS_FIX_VDOP +//#define GPS_FIX_PDOP +//#define GPS_FIX_LAT_ERR +//#define GPS_FIX_LON_ERR +//#define GPS_FIX_ALT_ERR +//#define GPS_FIX_GEOID_HEIGHT + +#endif diff --git a/software/firmware/libraries/NeoGPS/extras/configs/PUBX/NMEAGPS_cfg.h b/software/firmware/libraries/NeoGPS/extras/configs/PUBX/NMEAGPS_cfg.h new file mode 100644 index 0000000..9920301 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/configs/PUBX/NMEAGPS_cfg.h @@ -0,0 +1,286 @@ +#ifndef NMEAGPS_CFG_H +#define NMEAGPS_CFG_H + +//------------------------------------------------------ +// Enable/disable the parsing of specific sentences. +// +// Configuring out a sentence prevents it from being recognized; it +// will be completely ignored. (See also NMEAGPS_RECOGNIZE_ALL, below) +// +// FYI: Only RMC and ZDA contain date information. Other +// sentences contain time information. Both date and time are +// required if you will be doing time_t-to-clock_t operations. + +//#define NMEAGPS_PARSE_GGA +//#define NMEAGPS_PARSE_GLL +//#define NMEAGPS_PARSE_GSA +//#define NMEAGPS_PARSE_GSV +//#define NMEAGPS_PARSE_GST +//#define NMEAGPS_PARSE_RMC +//#define NMEAGPS_PARSE_VTG +//#define NMEAGPS_PARSE_ZDA + +//------------------------------------------------------ +// Select which sentence is sent *last* by your GPS device +// in each update interval. This can be used by your sketch +// to determine when the GPS quiet time begins, and thus +// when you can perform "some" time-consuming operations. + +#define LAST_SENTENCE_IN_INTERVAL (nmea_msg_t) NMEA_LAST_MSG+5 /* ubloxNMEA::PUBX_04 */ + +// If the NMEA_LAST_SENTENCE_IN_INTERVAL is not chosen +// correctly, GPS data may be lost because the sketch +// takes too long elsewhere when this sentence is received. +// Also, fix members may contain information from different +// time intervals (i.e., they are not coherent). +// +// If you don't know which sentence is the last one, +// use NMEAorder.ino to list them. You do not have to select +// the last sentence the device sends if you have disabled +// it. Just select the last sentence that you have *enabled*. + +//------------------------------------------------------ +// Enable/Disable coherency: +// +// If you need each fix to contain information that is only +// from the current update interval, you should uncomment +// this define. At the beginning of the next interval, +// the accumulating fix will start out empty. When +// the LAST_SENTENCE_IN_INTERVAL arrives, the valid +// fields will be coherent. + +//#define NMEAGPS_COHERENT + +// With IMPLICIT merging, fix() will be emptied when the +// next sentence begins. +// +// With EXPLICIT or NO merging, the fix() was already +// being initialized. +// +// If you use the fix-oriented methods available() and read(), +// they will empty the current fix for you automatically. +// +// If you use the character-oriented method decode(), you should +// empty the accumulating fix by testing and clearing the +// 'intervalComplete' flag in the same way that available() does. + +//------------------------------------------------------ +// Choose how multiple sentences are merged: +// 1) No merging +// Each sentence fills out its own fix; there could be +// multiple sentences per interval. +// 2) EXPLICIT_MERGING +// All sentences in an interval are *safely* merged into one fix. +// NMEAGPS_FIX_MAX must be >= 1. +// An interval is defined by NMEA_LAST_SENTENCE_IN_INTERVAL. +// 3) IMPLICIT_MERGING +// All sentences in an interval are merged into one fix, with +// possible data loss. If a received sentence is rejected for +// any reason (e.g., a checksum error), all the values are suspect. +// The fix will be cleared; no members will be valid until new +// sentences are received and accepted. This uses less RAM. +// An interval is defined by NMEA_LAST_SENTENCE_IN_INTERVAL. +// Uncomment zero or one: + +#define NMEAGPS_EXPLICIT_MERGING +//#define NMEAGPS_IMPLICIT_MERGING + +#ifdef NMEAGPS_IMPLICIT_MERGING + #define NMEAGPS_MERGING NMEAGPS::IMPLICIT_MERGING + + // When accumulating, nothing is done to the fix at the + // beginning of every sentence... + #ifdef NMEAGPS_COHERENT + // ...unless COHERENT is enabled and a new interval is starting + #define NMEAGPS_INIT_FIX(m) \ + if (intervalComplete()) { intervalComplete( false ); m.valid.init(); } + #else + #define NMEAGPS_INIT_FIX(m) + #endif + + // ...but we invalidate one part when it starts to get parsed. It *may* get + // validated when the parsing is finished. + #define NMEAGPS_INVALIDATE(m) m_fix.valid.m = false + +#else + + #ifdef NMEAGPS_EXPLICIT_MERGING + #define NMEAGPS_MERGING NMEAGPS::EXPLICIT_MERGING + #else + #define NMEAGPS_MERGING NMEAGPS::NO_MERGING + #define NMEAGPS_NO_MERGING + #endif + + // When NOT accumulating, invalidate the entire fix at the + // beginning of every sentence + #define NMEAGPS_INIT_FIX(m) m.valid.init() + + // ...so the individual parts do not need to be invalidated as they are parsed + #define NMEAGPS_INVALIDATE(m) + +#endif + +#if ( defined(NMEAGPS_NO_MERGING) + \ + defined(NMEAGPS_IMPLICIT_MERGING) + \ + defined(NMEAGPS_EXPLICIT_MERGING) ) > 1 + #error Only one MERGING technique should be enabled in NMEAGPS_cfg.h! +#endif + +//------------------------------------------------------ +// Define the fix buffer size. The NMEAGPS object will hold on to +// this many fixes before an overrun occurs. This can be zero, +// but you have to be more careful about using gps.fix() structure, +// because it will be modified as characters are received. + +#define NMEAGPS_FIX_MAX 1 + +#if defined(NMEAGPS_EXPLICIT_MERGING) && (NMEAGPS_FIX_MAX == 0) + #error You must define FIX_MAX >= 1 to allow EXPLICIT merging in NMEAGPS_cfg.h +#endif + +//------------------------------------------------------ +// Enable/Disable interrupt-style processing of GPS characters +// If you are using one of the NeoXXSerial libraries, +// to attachInterrupt, this must be defined. +// Otherwise, it must be commented out. + +//#define NMEAGPS_INTERRUPT_PROCESSING + +#ifdef NMEAGPS_INTERRUPT_PROCESSING + #define NMEAGPS_PROCESSING_STYLE NMEAGPS::PS_INTERRUPT +#else + #define NMEAGPS_PROCESSING_STYLE NMEAGPS::PS_POLLING +#endif + +//------------------------------------------------------ +// Enable/disable the talker ID, manufacturer ID and proprietary message processing. +// +// First, some background information. There are two kinds of NMEA sentences: +// +// 1. Standard NMEA sentences begin with "$ttccc", where +// "tt" is the talker ID, and +// "ccc" is the variable-length sentence type (i.e., command). +// +// For example, "$GPGLL,..." is a GLL sentence (Geographic Lat/Long) +// transmitted by talker "GP". This is the most common talker ID. Some +// devices may report "$GNGLL,..." when a mix of GPS and non-GPS +// satellites have been used to determine the GLL data. +// +// 2. Proprietary NMEA sentences (i.e., those unique to a particular +// manufacturer) begin with "$Pmmmccc", where +// "P" is the NMEA-defined prefix indicator for proprietary messages, +// "mmm" is the 3-character manufacturer ID, and +// "ccc" is the variable-length sentence type (it can be empty). +// +// No validation of manufacturer ID and talker ID is performed in this +// base class. For example, although "GP" is a common talker ID, it is not +// guaranteed to be transmitted by your particular device, and it IS NOT +// REQUIRED. If you need validation of these IDs, or you need to use the +// extra information provided by some devices, you have two independent +// options: +// +// 1. Enable SAVING the ID: When /decode/ returns DECODE_COMPLETED, the +// /talker_id/ and/or /mfr_id/ members will contain ID bytes. The entire +// sentence will be parsed, perhaps modifying members of /fix/. You should +// enable one or both IDs if you want the information in all sentences *and* +// you also want to know the ID bytes. This adds two bytes of RAM for the +// talker ID, and 3 bytes of RAM for the manufacturer ID. +// +// 2. Enable PARSING the ID: The virtual /parse_talker_id/ and +// /parse_mfr_id/ will receive each ID character as it is parsed. If it +// is not a valid ID, return /false/ to abort processing the rest of the +// sentence. No CPU time will be wasted on the invalid sentence, and no +// /fix/ members will be modified. You should enable this if you want to +// ignore some IDs. You must override /parse_talker_id/ and/or +// /parse_mfr_id/ in a derived class. +// + +//#define NMEAGPS_SAVE_TALKER_ID +//#define NMEAGPS_PARSE_TALKER_ID + +#define NMEAGPS_PARSE_PROPRIETARY +#ifdef NMEAGPS_PARSE_PROPRIETARY + //#define NMEAGPS_SAVE_MFR_ID + #define NMEAGPS_PARSE_MFR_ID +#endif + +//------------------------------------------------------ +// Enable/disable tracking the current satellite array and, +// optionally, all the info for each satellite. +// + +//#define NMEAGPS_PARSE_SATELLITES +//#define NMEAGPS_PARSE_SATELLITE_INFO + +#ifdef NMEAGPS_PARSE_SATELLITES + #define NMEAGPS_MAX_SATELLITES (20) + + #ifndef GPS_FIX_SATELLITES + #error GPS_FIX_SATELLITES must be defined in GPSfix.h! + #endif + +#endif + +#if defined(NMEAGPS_PARSE_SATELLITE_INFO) & \ + !defined(NMEAGPS_PARSE_SATELLITES) + #error NMEAGPS_PARSE_SATELLITES must be defined! +#endif + +//------------------------------------------------------ +// Enable/disable gathering interface statistics: +// CRC errors and number of sentences received + +//#define NMEAGPS_STATS + +//------------------------------------------------------ +// Configuration item for allowing derived types of NMEAGPS. +// If you derive classes from NMEAGPS, you *must* define NMEAGPS_DERIVED_TYPES. +// If not defined, virtuals are not used, with a slight size (2 bytes) and +// execution time savings. + +#define NMEAGPS_DERIVED_TYPES + +#ifdef NMEAGPS_DERIVED_TYPES + #define NMEAGPS_VIRTUAL virtual +#else + #define NMEAGPS_VIRTUAL +#endif + +//----------------------------------- +// See if DERIVED_TYPES is required +#if (defined(NMEAGPS_PARSE_TALKER_ID) | defined(NMEAGPS_PARSE_MFR_ID)) & \ + !defined(NMEAGPS_DERIVED_TYPES) + #error You must define NMEAGPS_DERIVED_TYPES in NMEAGPS.h in order to parse Talker and/or Mfr IDs! +#endif + +//------------------------------------------------------ +// Some devices may omit trailing commas at the end of some +// sentences. This may prevent the last field from being +// parsed correctly, because the parser for some types keep +// the value in an intermediate state until the complete +// field is received (e.g., parseDDDMM, parseFloat and +// parseZDA). +// +// Enabling this will inject a simulated comma when the end +// of a sentence is received and the last field parser +// indicated that it still needs one. + +//#define NMEAGPS_COMMA_NEEDED + +//------------------------------------------------------ +// Some applications may want to recognize a sentence type +// without actually parsing any of the fields. Uncommenting +// this define will allow the nmeaMessage member to be set +// when *any* standard message is seen, even though that +// message is not enabled by a NMEAGPS_PARSE_xxx define above. +// No valid flags will be true for those sentences. + +//#define NMEAGPS_RECOGNIZE_ALL + +//------------------------------------------------------ +// Sometimes, a little extra space is needed to parse an intermediate form. +// This config items enables extra space. + +//#define NMEAGPS_PARSING_SCRATCHPAD + +#endif \ No newline at end of file diff --git a/software/firmware/libraries/NeoGPS/extras/configs/PUBX/NeoGPS_cfg.h b/software/firmware/libraries/NeoGPS/extras/configs/PUBX/NeoGPS_cfg.h new file mode 100644 index 0000000..7ad6b70 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/configs/PUBX/NeoGPS_cfg.h @@ -0,0 +1,85 @@ +#ifndef NEOGPS_CFG +#define NEOGPS_CFG + +/** + * Enable/disable packed data structures. + * + * Enabling packed data structures will use two less-portable language + * features of GCC to reduce RAM requirements. Although it was expected to slightly increase execution time and code size, the reverse is true on 8-bit AVRs: the code is smaller and faster with packing enabled. + * + * Disabling packed data structures will be very portable to other + * platforms. NeoGPS configurations will use slightly more RAM, and on + * 8-bit AVRs, the speed is slightly slower, and the code is slightly + * larger. There may be no choice but to disable packing on processors + * that do not support packed structures. + * + * There may also be compiler-specific switches that affect packing and the + * code which accesses packed members. YMMV. + **/ + +#ifdef __AVR__ + #define NEOGPS_PACKED_DATA +#endif + +//------------------------------------------------------------------------ +// Based on the above define, choose which set of packing macros should +// be used in the rest of the NeoGPS package. Do not change these defines. + +#ifdef NEOGPS_PACKED_DATA + + // This is for specifying the number of bits to be used for a + // member of a struct. Booleans are typically one bit. + #define NEOGPS_BF(b) :b + + // This is for requesting the compiler to pack the struct or class members + // "as closely as possible". This is a compiler-dependent interpretation. + #define NEOGPS_PACKED __attribute__((packed)) + +#else + + // Let the compiler do whatever it wants. + + #define NEOGPS_PACKED + #define NEOGPS_BF(b) + +#endif + +/* + * Accommodate C++ compiler and IDE changes. + * + * Declaring constants as class data instead of instance data helps avoid + * collisions with #define names, and allows the compiler to perform more + * checks on their usage. + * + * Until C++ 10 and IDE 1.6.8, initialized class data constants + * were declared like this: + * + * static const = ; + * + * Now, non-simple types (e.g., float) must be declared as + * + * static constexpr = ; + * + * The good news is that this allows the compiler to optimize out an + * expression that is "promised" to be "evaluatable" as a constant. + * The bad news is that it introduces a new language keyword, and the old + * code raises an error. + * + * TODO: Evaluate the requirement for the "static" keyword. + * TODO: Evaluate using a C++ version preprocessor symbol for the #if. + * + * The CONST_CLASS_DATA define will expand to the appropriate keywords. + * + */ + +#if ARDUINO < 10606 + + #define CONST_CLASS_DATA static const + +#else + + #define CONST_CLASS_DATA static constexpr + +#endif + +#endif diff --git a/software/firmware/libraries/NeoGPS/extras/configs/Speed/GPSfix_cfg.h b/software/firmware/libraries/NeoGPS/extras/configs/Speed/GPSfix_cfg.h new file mode 100644 index 0000000..b22badb --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/configs/Speed/GPSfix_cfg.h @@ -0,0 +1,35 @@ +#ifndef GPS_FIX_CFG +#define GPS_FIX_CFG + +/** + * Enable/disable the storage for the members of a fix. + * + * Disabling a member prevents it from being parsed from a received message. + * The disabled member cannot be accessed or stored, and its validity flag + * would not be available. It will not be declared, and code that uses that + * member will not compile. + * + * DATE and TIME are somewhat coupled in that they share a single `time_t`, + * but they have separate validity flags. + * + * See also note regarding the DOP members, below. + * + */ + +//#define GPS_FIX_DATE +//#define GPS_FIX_TIME +//#define GPS_FIX_LOCATION +//#define GPS_FIX_LOCATION_DMS +//#define GPS_FIX_ALTITUDE +#define GPS_FIX_SPEED +//#define GPS_FIX_HEADING +//#define GPS_FIX_SATELLITES +//#define GPS_FIX_HDOP +//#define GPS_FIX_VDOP +//#define GPS_FIX_PDOP +//#define GPS_FIX_LAT_ERR +//#define GPS_FIX_LON_ERR +//#define GPS_FIX_ALT_ERR +//#define GPS_FIX_GEOID_HEIGHT + +#endif diff --git a/software/firmware/libraries/NeoGPS/extras/configs/Speed/NMEAGPS_cfg.h b/software/firmware/libraries/NeoGPS/extras/configs/Speed/NMEAGPS_cfg.h new file mode 100644 index 0000000..a41564c --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/configs/Speed/NMEAGPS_cfg.h @@ -0,0 +1,286 @@ +#ifndef NMEAGPS_CFG_H +#define NMEAGPS_CFG_H + +//------------------------------------------------------ +// Enable/disable the parsing of specific sentences. +// +// Configuring out a sentence prevents it from being recognized; it +// will be completely ignored. (See also NMEAGPS_RECOGNIZE_ALL, below) +// +// FYI: Only RMC and ZDA contain date information. Other +// sentences contain time information. Both date and time are +// required if you will be doing time_t-to-clock_t operations. + +//#define NMEAGPS_PARSE_GGA +//#define NMEAGPS_PARSE_GLL +//#define NMEAGPS_PARSE_GSA +//#define NMEAGPS_PARSE_GSV +//#define NMEAGPS_PARSE_GST +#define NMEAGPS_PARSE_RMC +//#define NMEAGPS_PARSE_VTG +//#define NMEAGPS_PARSE_ZDA + +//------------------------------------------------------ +// Select which sentence is sent *last* by your GPS device +// in each update interval. This can be used by your sketch +// to determine when the GPS quiet time begins, and thus +// when you can perform "some" time-consuming operations. + +#define LAST_SENTENCE_IN_INTERVAL NMEAGPS::NMEA_RMC + +// If the NMEA_LAST_SENTENCE_IN_INTERVAL is not chosen +// correctly, GPS data may be lost because the sketch +// takes too long elsewhere when this sentence is received. +// Also, fix members may contain information from different +// time intervals (i.e., they are not coherent). +// +// If you don't know which sentence is the last one, +// use NMEAorder.ino to list them. You do not have to select +// the last sentence the device sends if you have disabled +// it. Just select the last sentence that you have *enabled*. + +//------------------------------------------------------ +// Enable/Disable coherency: +// +// If you need each fix to contain information that is only +// from the current update interval, you should uncomment +// this define. At the beginning of the next interval, +// the accumulating fix will start out empty. When +// the LAST_SENTENCE_IN_INTERVAL arrives, the valid +// fields will be coherent. + +//#define NMEAGPS_COHERENT + +// With IMPLICIT merging, fix() will be emptied when the +// next sentence begins. +// +// With EXPLICIT or NO merging, the fix() was already +// being initialized. +// +// If you use the fix-oriented methods available() and read(), +// they will empty the current fix for you automatically. +// +// If you use the character-oriented method decode(), you should +// empty the accumulating fix by testing and clearing the +// 'intervalComplete' flag in the same way that available() does. + +//------------------------------------------------------ +// Choose how multiple sentences are merged: +// 1) No merging +// Each sentence fills out its own fix; there could be +// multiple sentences per interval. +// 2) EXPLICIT_MERGING +// All sentences in an interval are *safely* merged into one fix. +// NMEAGPS_FIX_MAX must be >= 1. +// An interval is defined by NMEA_LAST_SENTENCE_IN_INTERVAL. +// 3) IMPLICIT_MERGING +// All sentences in an interval are merged into one fix, with +// possible data loss. If a received sentence is rejected for +// any reason (e.g., a checksum error), all the values are suspect. +// The fix will be cleared; no members will be valid until new +// sentences are received and accepted. This uses less RAM. +// An interval is defined by NMEA_LAST_SENTENCE_IN_INTERVAL. +// Uncomment zero or one: + +#define NMEAGPS_EXPLICIT_MERGING +//#define NMEAGPS_IMPLICIT_MERGING + +#ifdef NMEAGPS_IMPLICIT_MERGING + #define NMEAGPS_MERGING NMEAGPS::IMPLICIT_MERGING + + // When accumulating, nothing is done to the fix at the + // beginning of every sentence... + #ifdef NMEAGPS_COHERENT + // ...unless COHERENT is enabled and a new interval is starting + #define NMEAGPS_INIT_FIX(m) \ + if (intervalComplete()) { intervalComplete( false ); m.valid.init(); } + #else + #define NMEAGPS_INIT_FIX(m) + #endif + + // ...but we invalidate one part when it starts to get parsed. It *may* get + // validated when the parsing is finished. + #define NMEAGPS_INVALIDATE(m) m_fix.valid.m = false + +#else + + #ifdef NMEAGPS_EXPLICIT_MERGING + #define NMEAGPS_MERGING NMEAGPS::EXPLICIT_MERGING + #else + #define NMEAGPS_MERGING NMEAGPS::NO_MERGING + #define NMEAGPS_NO_MERGING + #endif + + // When NOT accumulating, invalidate the entire fix at the + // beginning of every sentence + #define NMEAGPS_INIT_FIX(m) m.valid.init() + + // ...so the individual parts do not need to be invalidated as they are parsed + #define NMEAGPS_INVALIDATE(m) + +#endif + +#if ( defined(NMEAGPS_NO_MERGING) + \ + defined(NMEAGPS_IMPLICIT_MERGING) + \ + defined(NMEAGPS_EXPLICIT_MERGING) ) > 1 + #error Only one MERGING technique should be enabled in NMEAGPS_cfg.h! +#endif + +//------------------------------------------------------ +// Define the fix buffer size. The NMEAGPS object will hold on to +// this many fixes before an overrun occurs. This can be zero, +// but you have to be more careful about using gps.fix() structure, +// because it will be modified as characters are received. + +#define NMEAGPS_FIX_MAX 1 + +#if defined(NMEAGPS_EXPLICIT_MERGING) && (NMEAGPS_FIX_MAX == 0) + #error You must define FIX_MAX >= 1 to allow EXPLICIT merging in NMEAGPS_cfg.h +#endif + +//------------------------------------------------------ +// Enable/Disable interrupt-style processing of GPS characters +// If you are using one of the NeoXXSerial libraries, +// to attachInterrupt, this must be defined. +// Otherwise, it must be commented out. + +//#define NMEAGPS_INTERRUPT_PROCESSING + +#ifdef NMEAGPS_INTERRUPT_PROCESSING + #define NMEAGPS_PROCESSING_STYLE NMEAGPS::PS_INTERRUPT +#else + #define NMEAGPS_PROCESSING_STYLE NMEAGPS::PS_POLLING +#endif + +//------------------------------------------------------ +// Enable/disable the talker ID, manufacturer ID and proprietary message processing. +// +// First, some background information. There are two kinds of NMEA sentences: +// +// 1. Standard NMEA sentences begin with "$ttccc", where +// "tt" is the talker ID, and +// "ccc" is the variable-length sentence type (i.e., command). +// +// For example, "$GPGLL,..." is a GLL sentence (Geographic Lat/Long) +// transmitted by talker "GP". This is the most common talker ID. Some +// devices may report "$GNGLL,..." when a mix of GPS and non-GPS +// satellites have been used to determine the GLL data. +// +// 2. Proprietary NMEA sentences (i.e., those unique to a particular +// manufacturer) begin with "$Pmmmccc", where +// "P" is the NMEA-defined prefix indicator for proprietary messages, +// "mmm" is the 3-character manufacturer ID, and +// "ccc" is the variable-length sentence type (it can be empty). +// +// No validation of manufacturer ID and talker ID is performed in this +// base class. For example, although "GP" is a common talker ID, it is not +// guaranteed to be transmitted by your particular device, and it IS NOT +// REQUIRED. If you need validation of these IDs, or you need to use the +// extra information provided by some devices, you have two independent +// options: +// +// 1. Enable SAVING the ID: When /decode/ returns DECODE_COMPLETED, the +// /talker_id/ and/or /mfr_id/ members will contain ID bytes. The entire +// sentence will be parsed, perhaps modifying members of /fix/. You should +// enable one or both IDs if you want the information in all sentences *and* +// you also want to know the ID bytes. This adds two bytes of RAM for the +// talker ID, and 3 bytes of RAM for the manufacturer ID. +// +// 2. Enable PARSING the ID: The virtual /parse_talker_id/ and +// /parse_mfr_id/ will receive each ID character as it is parsed. If it +// is not a valid ID, return /false/ to abort processing the rest of the +// sentence. No CPU time will be wasted on the invalid sentence, and no +// /fix/ members will be modified. You should enable this if you want to +// ignore some IDs. You must override /parse_talker_id/ and/or +// /parse_mfr_id/ in a derived class. +// + +//#define NMEAGPS_SAVE_TALKER_ID +//#define NMEAGPS_PARSE_TALKER_ID + +//#define NMEAGPS_PARSE_PROPRIETARY +#ifdef NMEAGPS_PARSE_PROPRIETARY + //#define NMEAGPS_SAVE_MFR_ID + #define NMEAGPS_PARSE_MFR_ID +#endif + +//------------------------------------------------------ +// Enable/disable tracking the current satellite array and, +// optionally, all the info for each satellite. +// + +//#define NMEAGPS_PARSE_SATELLITES +//#define NMEAGPS_PARSE_SATELLITE_INFO + +#ifdef NMEAGPS_PARSE_SATELLITES + #define NMEAGPS_MAX_SATELLITES (20) + + #ifndef GPS_FIX_SATELLITES + #error GPS_FIX_SATELLITES must be defined in GPSfix.h! + #endif + +#endif + +#if defined(NMEAGPS_PARSE_SATELLITE_INFO) & \ + !defined(NMEAGPS_PARSE_SATELLITES) + #error NMEAGPS_PARSE_SATELLITES must be defined! +#endif + +//------------------------------------------------------ +// Enable/disable gathering interface statistics: +// CRC errors and number of sentences received + +//#define NMEAGPS_STATS + +//------------------------------------------------------ +// Configuration item for allowing derived types of NMEAGPS. +// If you derive classes from NMEAGPS, you *must* define NMEAGPS_DERIVED_TYPES. +// If not defined, virtuals are not used, with a slight size (2 bytes) and +// execution time savings. + +//#define NMEAGPS_DERIVED_TYPES + +#ifdef NMEAGPS_DERIVED_TYPES + #define NMEAGPS_VIRTUAL virtual +#else + #define NMEAGPS_VIRTUAL +#endif + +//----------------------------------- +// See if DERIVED_TYPES is required +#if (defined(NMEAGPS_PARSE_TALKER_ID) | defined(NMEAGPS_PARSE_MFR_ID)) & \ + !defined(NMEAGPS_DERIVED_TYPES) + #error You must define NMEAGPS_DERIVED_TYPES in NMEAGPS.h in order to parse Talker and/or Mfr IDs! +#endif + +//------------------------------------------------------ +// Some devices may omit trailing commas at the end of some +// sentences. This may prevent the last field from being +// parsed correctly, because the parser for some types keep +// the value in an intermediate state until the complete +// field is received (e.g., parseDDDMM, parseFloat and +// parseZDA). +// +// Enabling this will inject a simulated comma when the end +// of a sentence is received and the last field parser +// indicated that it still needs one. + +//#define NMEAGPS_COMMA_NEEDED + +//------------------------------------------------------ +// Some applications may want to recognize a sentence type +// without actually parsing any of the fields. Uncommenting +// this define will allow the nmeaMessage member to be set +// when *any* standard message is seen, even though that +// message is not enabled by a NMEAGPS_PARSE_xxx define above. +// No valid flags will be true for those sentences. + +//#define NMEAGPS_RECOGNIZE_ALL + +//------------------------------------------------------ +// Sometimes, a little extra space is needed to parse an intermediate form. +// This config items enables extra space. + +//#define NMEAGPS_PARSING_SCRATCHPAD + +#endif \ No newline at end of file diff --git a/software/firmware/libraries/NeoGPS/extras/configs/Speed/NeoGPS_cfg.h b/software/firmware/libraries/NeoGPS/extras/configs/Speed/NeoGPS_cfg.h new file mode 100644 index 0000000..7ad6b70 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/configs/Speed/NeoGPS_cfg.h @@ -0,0 +1,85 @@ +#ifndef NEOGPS_CFG +#define NEOGPS_CFG + +/** + * Enable/disable packed data structures. + * + * Enabling packed data structures will use two less-portable language + * features of GCC to reduce RAM requirements. Although it was expected to slightly increase execution time and code size, the reverse is true on 8-bit AVRs: the code is smaller and faster with packing enabled. + * + * Disabling packed data structures will be very portable to other + * platforms. NeoGPS configurations will use slightly more RAM, and on + * 8-bit AVRs, the speed is slightly slower, and the code is slightly + * larger. There may be no choice but to disable packing on processors + * that do not support packed structures. + * + * There may also be compiler-specific switches that affect packing and the + * code which accesses packed members. YMMV. + **/ + +#ifdef __AVR__ + #define NEOGPS_PACKED_DATA +#endif + +//------------------------------------------------------------------------ +// Based on the above define, choose which set of packing macros should +// be used in the rest of the NeoGPS package. Do not change these defines. + +#ifdef NEOGPS_PACKED_DATA + + // This is for specifying the number of bits to be used for a + // member of a struct. Booleans are typically one bit. + #define NEOGPS_BF(b) :b + + // This is for requesting the compiler to pack the struct or class members + // "as closely as possible". This is a compiler-dependent interpretation. + #define NEOGPS_PACKED __attribute__((packed)) + +#else + + // Let the compiler do whatever it wants. + + #define NEOGPS_PACKED + #define NEOGPS_BF(b) + +#endif + +/* + * Accommodate C++ compiler and IDE changes. + * + * Declaring constants as class data instead of instance data helps avoid + * collisions with #define names, and allows the compiler to perform more + * checks on their usage. + * + * Until C++ 10 and IDE 1.6.8, initialized class data constants + * were declared like this: + * + * static const = ; + * + * Now, non-simple types (e.g., float) must be declared as + * + * static constexpr = ; + * + * The good news is that this allows the compiler to optimize out an + * expression that is "promised" to be "evaluatable" as a constant. + * The bad news is that it introduces a new language keyword, and the old + * code raises an error. + * + * TODO: Evaluate the requirement for the "static" keyword. + * TODO: Evaluate using a C++ version preprocessor symbol for the #if. + * + * The CONST_CLASS_DATA define will expand to the appropriate keywords. + * + */ + +#if ARDUINO < 10606 + + #define CONST_CLASS_DATA static const + +#else + + #define CONST_CLASS_DATA static constexpr + +#endif + +#endif diff --git a/software/firmware/libraries/NeoGPS/extras/doc/Acknowledgements.md b/software/firmware/libraries/NeoGPS/extras/doc/Acknowledgements.md new file mode 100644 index 0000000..4c10d3d --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/doc/Acknowledgements.md @@ -0,0 +1,5 @@ +Acknowledgements +========== +Mikal Hart's [TinyGPS](https://github.com/mikalhart/TinyGPS) for the generic `decode` approach. + +tht's [initial implementation](http://forum.arduino.cc/index.php?topic=150299.msg1863220#msg1863220) of a Cosa `IOStream::Device`. diff --git a/software/firmware/libraries/NeoGPS/extras/doc/CharOriented.md b/software/firmware/libraries/NeoGPS/extras/doc/CharOriented.md new file mode 100644 index 0000000..092a240 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/doc/CharOriented.md @@ -0,0 +1,64 @@ +Character-oriented methods +=========================== + +Sometimes, individual characters or sentences must be processed or filtered, long before a fix structure is completed (i.e., `available()`). In this advanced technique, your sketch should read each character and pass it to the character-oriented method `gps.decode()`: +``` +void loop() +{ + while (serial.available()) { + char c = serial.read(); + if (gps.decode( c ) == DECODE_COMPLETED) { + ... do something with gps.fix()... + } +``` +As `gps` decodes those bytes, it will gradually fill out the pieces of its internal fix structure, `gps.fix()` (members described [here](Data%20Model.md). When you want to use some of the fix data, you can access it like this: +``` + Serial.print( gps.fix().latitude() ); + Serial.print( ',' ); + Serial.println( gps.fix().longitude() ); +``` +However, you must wait for the sentence to be completely decoded. You can't access `gps.fix()` unless you know that it is COMPLETED. You must copy it to another fix variable if you need to access it at any time. + +**IMPORTANT:** `gps.fix()` **IS ONLY VALID WHEN:** + - `gps.decode()` just returned `DECODE_COMPLETED`, or + - `gps.is_safe()` + +This is because `gps.fix().speed` may be half-formed. You must either do all your accessing immediately after `gps.decode()` returns `DECODE_COMPLETED`: +``` +void loop() +{ + // At this point of the code, speed could be half-decoded. + if (gps.fix().speed <= 5) // NOT A GOOD IDEA! + Serial.println( F("Too slow!") ); + + while (serial.available()) { + char c = serial.read(); + if (gps.decode( serial.read() ) == NMEAGPS::DECODE_COMPLETED) { + + // Access any piece of gps.fix() in here... + + if (gps.fix().speed <= 5) // OK! + Serial.println( F("Too slow!") ); + + if (gps.fix().lat ... + } + } + +``` +Or you must call `gps.is_safe()` before using `gps.fix()`. It is safest to copy `gps.fix()` into your own variable for use at any time: +``` +gps_fix my_fix; + +void loop() +{ + while (serial.available()) { + char c = serial.read(); + if (gps.decode( serial.read() ) == NMEAGPS::DECODE_COMPLETED) { + my_fix = gps.fix(); // save for later... + } + } + + if (my_fix.speed <= 5) // OK + DigitalWrite( UNDERSPEED_INDICATOR, HIGH ); +``` +Although the character-oriented program structure gives you a finer granularity of control, you must be more careful when accessing `gps.fix()`. diff --git a/software/firmware/libraries/NeoGPS/extras/doc/Choosing.md b/software/firmware/libraries/NeoGPS/extras/doc/Choosing.md new file mode 100644 index 0000000..511af86 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/doc/Choosing.md @@ -0,0 +1,231 @@ +# Choosing your configuration +There are only a few configurations provided by examples. If your application needs something slightly different, here is a general configuration process. + +## What number do you want? +First, decide which data members of `gps_fix` and `NMEAGPS` you need (see [Data Model](Data Model.md) for member descriptions). Those members **must** be enabled in `GPSfix_cfg.h`. + +Next, figure out what messages can fill out those members, because those messages **must** be enabled in `NMEAGPS_cfg.h`. Here is a table of the NMEA messages parsed by NeoGPS, and which data members they affect: + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

Message

Data Member

GGA


GLL


GSA


GST


GSV


RMC


VTG


ZDA


PUBX
001


PUBX
041


class gps_fix

status

*** ** *

date2

* * *

time2

** * * ***

lat/lon

** * *

altitude

* *

speed

** *

heading

** *

lat, lon, alt error

*

satellites

* * *

HDOP

* * *

VDOP

* *

PDOP

*

TDOP

*

class NMEAGPS

satellite IDs

* *

satellite azimuth,
  elevation and
  signal strength

*
+ +This table illustrates the poor design of the NMEA message set: it requires multiple messages to deliver a complete fix (i.e., all members of `gps_fix`). This also explains why many manufacturers provide proprietary messages that *are* more complete. Above, you can see that the `$PUBX,00`1 message contains all members except `date`. + +While the manufacturer's specification will document all sentences supported for your device, you can also find general descriptions of many NMEA sentences [here](http://www.gpsinformation.org/dale/nmea.htm), [here](http://aprs.gids.nl/nmea/) or [here](http://www.catb.org/gpsd/NMEA.txt). + +
+ + +1 The NMEA proprietary messages "PUBX" are only availble in the `ubloxNMEA` class. See [ublox-specific instructions](ublox.md) for adding this class to your configuration. + +2 Date and time are both stored in one member of `gps_fix`, called `dateTime`. The `fix.dateTime` member is a C++ class that has both date-oriented members (Date, Month and Year) and time-oriented members (Hours, Minutes and Seconds). See [NeoTime.h](/src/NeoTime.h) for the complete description and capabilities of the `dateTime` member, such as date/time arithmetic and conversion to/from seconds since the epoch. Hundredths of a second are stored in a separate member of `gps_fix`, called `dateTime_cs`, and can also be accessed with the functions `dateTime_ms()` and `dateTime_us()`. diff --git a/software/firmware/libraries/NeoGPS/extras/doc/Coherency.md b/software/firmware/libraries/NeoGPS/extras/doc/Coherency.md new file mode 100644 index 0000000..0de4df6 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/doc/Coherency.md @@ -0,0 +1,13 @@ +Coherency +========== +Coherency guarantees that all members of a fix are from the same GPS time. For example, lat/long members may have been set by the newest sentence, but the altitude may be from the previous time interval. Most applications do not care that the fix members are not coherent. However, if you are controlling a drone or other autonomous vehicle, you may need coherency. + +NeoGPS achieves coherency by detecting the "quiet" time between batches of sentences. When new data starts coming in, the fix will get emptied or initialized, and all new sentences will be accumulated in the internal fix. + +If coherency is desired, **you must choose the correct LAST_SENTENCE_IN_INTERVAL.** If you're not sure which sentence is sent last (and therefore, when the quiet time begins), use NMEAorder.ino to analyze your GPS device. + +You must also use **EXPLICIT_MERGING**. Implicit merging cannot be used with coherency is because a sentence has to be parsed to know its timestamp. If it were implicitly merged, the old data would not have been invalidated. Invalidating data from a previous update period must be performed _before_ the sentence parsing begins. That can only be accomplished with a second 'safe' copy of the fix data and explicit merging (i.e., FIX_MAX >= 1). With implicit merging, new data has already been mixed with old data by the time DECODE_COMPLETED occurs and timestamps can be checked. + +When you have correctly chosen the LAST_SENTENCE_IN_INTERVAL *and* EXPLICIT_MERGING, the fix-oriented methods `available` and `read()` will return a coherent fix. + +NOTE: If you use the [character-oriented methods](CharOriented.md) `decode`, `is_safe` and `fix()` to handle individual sentences, you must check `intervalComplete()` to know when the GPS update interval is completed, and the GPS quiet time has started. diff --git a/software/firmware/libraries/NeoGPS/extras/doc/Configurations.md b/software/firmware/libraries/NeoGPS/extras/doc/Configurations.md new file mode 100644 index 0000000..3b12473 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/doc/Configurations.md @@ -0,0 +1,260 @@ +Configuration +============= +All configuration items are conditional compilations: a `#define` controls an `#if`/`#endif` section. +Comment out any items to be disabled or excluded from your build. +Where possible, checks are performed to verify that you have chosen a "valid" +configuration: you may see `#error` messages in the build log. See also [Choosing Your Configuration](Choosing.md) and [Troubleshooting](Troubleshooting.md). + +# class gps_fix +The following configuration items are near the top of GPSfix_cfg.h: +``` +// Enable/Disable individual parts of a fix, as parsed from fields of a $GPxxx sentence +#define GPS_FIX_DATE +#define GPS_FIX_TIME +#define GPS_FIX_LOCATION +#define GPS_FIX_LOCATION_DMS +#define GPS_FIX_ALTITUDE +#define GPS_FIX_SPEED +#define GPS_FIX_HEADING +#define GPS_FIX_SATELLITES +#define GPS_FIX_HDOP +#define GPS_FIX_VDOP +#define GPS_FIX_PDOP +#define GPS_FIX_LAT_ERR +#define GPS_FIX_LON_ERR +#define GPS_FIX_ALT_ERR +#define GPS_FIX_GEOID_HEIGHT +``` +See the [Data Model](Data%20Model.md) page and `GPSfix.h` for the corresponding members that are enabled or disabled by these defines. + +======================== +# class NMEAGPS +The following configuration items are near the top of NMEAGPS_cfg.h. +#### Enable/Disable parsing the fields of a $GPxxx sentence +``` +#define NMEAGPS_PARSE_GGA +#define NMEAGPS_PARSE_GLL +#define NMEAGPS_PARSE_GSA +#define NMEAGPS_PARSE_GSV +#define NMEAGPS_PARSE_GST +#define NMEAGPS_PARSE_RMC +#define NMEAGPS_PARSE_VTG +#define NMEAGPS_PARSE_ZDA +``` +#### Select the last sentence in an update interval +This is used to determine when the GPS quiet time begins and when a batch of coherent sentences have been merged. It is crucial to know when fixes can be marked as available, and when you can perform some time-consuming operations. +``` +#define LAST_SENTENCE_IN_INTERVAL NMEAGPS::NMEA_GLL +``` +You can use `NMEAorder.ino` to determine the last sentence sent by your device. +#### Enable/Disable No, Implicit, Explicit Merging +If you want NO merging, comment out both defines. Otherwise, uncomment the IMPLICIT or EXPLICIT define. +``` +#define NMEAGPS_EXPLICIT_MERGING +//#define NMEAGPS_IMPLICIT_MERGING +``` +See [Merging](Merging.md) for more information. +#### Define the fix buffer size. +The NMEAGPS object will hold on to this many fixes before an overrun occurs. The buffered fixes can be obtained by calling `gps.read()`. You can specify zero, but you have to be sure to call `gps.read()` before the next sentence starts. +``` +#define NMEAGPS_FIX_MAX 1 +``` +#### Enable/Disable interrupt-style processing +Define how fixes are dropped when the fix buffer is full. +``` +#define NMEAGPS_KEEP_NEWEST_FIXES true +``` + true = the oldest fix will be dropped, and the new fix will be saved. + false = the new fix will be dropped, and all old fixes will be saved. +#### Enable/Disable interrupt-style processing +If you are using one of the NeoXXSerial libraries to `attachInterrupt`, this must be uncommented to guarantee safe access to the buffered fixes with `gps.read()`. For normal polling-style processing, it must be commented out. +``` +//#define NMEAGPS_INTERRUPT_PROCESSING +``` +#### Enable/Disable the talker ID and manufacturer ID processing. +There are two kinds of NMEA sentences: + +1. Standard NMEA sentences begin with "$ttccc", where + "tt" is the talker ID (e.g., GP), and + "ccc" is the variable-length sentence type (e.g., RMC). + + For example, "$GPGLL,..." is a GLL sentence (Geographic Lat/Long) + transmitted by talker "GP". This is the most common talker ID. Some devices + may report "$GNGLL,..." when a mix of GPS and non-GPS satellites have been + used to determine the GLL data (e.g., GLONASS+GPS). + +2. Proprietary NMEA sentences (i.e., those unique to a particular manufacturer) + begin with "$Pmmmccc", where + "P" is the NMEA-defined prefix indicator for proprietary messages, + "mmm" is the 3-character manufacturer ID, and + "ccc" is the variable-length sentence type (it can be empty). + +No validation of manufacturer ID and talker ID is performed in this +base class. For example, although "GP" is a common talker ID, it is not +guaranteed to be transmitted by your particular device, and it IS NOT REQUIRED. +If you need validation of these IDs, or you need to use the extra information +provided by some devices, you have two independent options: + +1. Enable SAVING the ID: When `decode` returns DECODE_COMPLETED, the `talker_id` +and/or `mfr_id` members will contain ID bytes. The entire sentence will be +parsed, perhaps modifying members of `fix`. You should enable one or both IDs +if you want the information in all sentences *and* you also want to know the ID +bytes. This adds 2 bytes of RAM for the talker ID, and 3 bytes of RAM for the +manufacturer ID. + +2. Enable PARSING the ID: The virtual `parse_talker_id` and `parse_mfr_id` will +receive each ID character as it is received. If it is not a valid ID, return +`false` to abort processing the rest of the sentence. No CPU time will be wasted +on the invalid sentence, and no `fix` members will be modified. You should +enable this if you want to ignore some IDs. You must override `parse_talker_id` +and/or `parse_mfr_id` in a derived class. + +``` +#define NMEAGPS_SAVE_TALKER_ID +#define NMEAGPS_PARSE_TALKER_ID + +#define NMEAGPS_SAVE_MFR_ID +#define NMEAGPS_PARSE_MFR_ID +``` +#### Enable/Disable parsing of NMEA proprietary messages +If you are deriving a class from NMEAGPS to parse proprietary messages, you must uncomment this define: +``` +//#define NMEAGPS_PARSE_PROPRIETARY +``` +#### Enable/Disable tracking the current satellite array +You can also enable tracking the detailed information for each satellite, and how many satellites you want to track. +Although many GPS receivers claim to have 66 channels of tracking, 16 is usually the maximum number of satellites +tracked at any one time. +``` +#define NMEAGPS_PARSE_SATELLITES +#define NMEAGPS_PARSE_SATELLITE_INFO +#define NMEAGPS_MAX_SATELLITES (20) +``` +#### Enable/disable gathering interface statistics: +Uncommenting this define will allow counting the number of sentences and characters received and the number of checksum (CS) errors. If the CS errors are increasing, you could be losing characters or the connection could be noisy. +``` +#define NMEAGPS_STATS +``` +#### Enable/disable UTC sub-second resolution + +Fixes will be received at approximately 1-second intervals, but there can +be 30ms *or more* of variance in those intervals. If you need to know the exact UTC time at *any* time, +with sub-second accuracy, you must calculate the +offset between the Arduino micros() clock and the UTC time in a received fix. +There are two ways to do this: + +**1. When the GPS quiet time ends and the new update interval begins.** + +The timestamp will be set when the first character (the '$') of +the new batch of sentences arrives from the GPS device. This is fairly +accurate, but it will be delayed from the PPS edge by the GPS device's +fix calculation time (usually ~100us). There is very little variance +in this calculation time (usually < 30us), so all timestamps are +delayed by a nearly-constant amount. +``` + #define NMEAGPS_TIMESTAMP_FROM_INTERVAL +``` +NOTE: At update rates higher than 1Hz, the updates may arrive with +some increasing variance. + +**2. From the PPS pin of the GPS module.** + +It is up to the application developer to decide how to capture that event. For example, you could: + +a) simply poll for it in loop and call UTCsecondStart(micros()); + +b) use attachInterrupt to call a Pin Change Interrupt ISR to save + the micros() at the time of the interrupt (see NMEAGPS.h), or + +c) connect the PPS to an Input Capture pin. Set the + associated TIMER frequency, calculate the elapsed time + since the PPS edge, and add that to the current micros(). +``` + #define NMEAGPS_TIMESTAMP_FROM_PPS +``` +#### Enable/Disable derived types +Although normally disabled, this must be enabled if you derive any classes from NMEAGPS. +``` +//#define NMEAGPS_DERIVED_TYPES +``` + +The ublox-specific files require this define (see [ublox](ublox.md) section). +#### Enable/Disable guaranteed comma field separator +Some devices may omit trailing commas at the end of some sentences. This may prevent the last field from being parsed correctly, because the parser for some types keep the value in an intermediate state until the complete field is received (e.g., parseDDDMM, parseFloat and parseZDA). + +Enabling this will inject a simulated comma when the end of a sentence is received and the last field parser indicated that it still needs one. +``` +//#define NMEAGPS_COMMA_NEEDED +``` +#### Enable/Disable recognizing all sentence types +Some applications may want to recognize a sentence type without actually parsing any of the fields. Uncommenting this define will allow the `gps.nmeaMessage` member to be set when *any* standard message is seen, even though that message is not enabled by a `#defineNMEAGPS_PARSE_xxx`. No valid flags will be true for disabled sentences. +``` +#define NMEAGPS_RECOGNIZE_ALL +``` +#### Enable/Disable parsing scratchpad +Sometimes, a little extra space is needed to parse an intermediate form. This define enables extra space. Parsers that require the scratchpad can either `#ifdef` an `#error` when the scratchpad is disabled, or let the compiler generate an error when attempting to use the `scratchpad` union (see NMEAGPS.h). +``` +//#define NMEAGPS_PARSING_SCRATCHPAD +``` + +======================== +# ublox-specific configuration items + +See the [ublox](ublox.md) section. + +======================== +# Floating-point output. +Streamers.cpp is used by the example programs for printing members of `fix()`. It is not required for parsing the GPS data stream, and this file may be deleted. It is an example of checking validity flags and formatting the various members of `fix()` for textual streams (e.g., Serial prints or SD writes). + +Streamers.cpp has one configuration item: +``` +#define USE_FLOAT +``` +This is local to this file, and is only used by the example programs. This file is _not_ required unless you need to stream one of these types: bool, char, uint8_t, int16_t, uint16_t, int32_t, uint32_t, F() strings, `gps_fix` or `NMEAGPS`. + +Most example programs have a choice for displaying fix information once per day. (Untested!) +``` +#define PULSE_PER_DAY +``` +======================== +# Platforms +The following configuration items are near the top of NeoGPS_cfg.h. +#### Enable/Disable packed bitfields +``` +#define NEOGPS_PACKED_DATA +``` +8-bit Arduino platforms can address memory by bytes or words. This allows passing data by reference or +address, as long as it is one or more bytes in length. The `gps_fix` class has some members which are +only one bit; these members cannot be passed by reference or address, only by value. NeoGPS uses an +appropriate passing technique, depending on the size of these members. + +32-bit Arduino platforms require *all* memory accesses to be 32-bit aligned, which precludes passing +bitfield, byte, or word members by reference or address. Rather than penalize the 8-bit platforms with +unpacked classes and structs, the `NEOGPS_PACKED_DATA` can be disabled on 32-bit platforms. This +increases the RAM requirements, but these platforms typically have more available RAM. + +======================== +# Typical configurations +A few common configurations are defined as follows + +**Minimal**: no fix members, no messages (pulse-per-second only) + +**DTL**: date, time, lat/lon, GPRMC messsage only. + +**Nominal**: date, time, lat/lon, altitude, speed, heading, number of +satellites, HDOP, GPRMC and GPGGA messages. + +**Full**: Nominal plus talker ID, VDOP, PDOP, lat/lon/alt errors, satellite array with satellite info, all messages, and parser statistics. + +**PUBX**: Nominal fix items, standard sentences _disabled_, proprietary sentences PUBX 00 and 04 enabled, and required PARSE_MFR_ID and DERIVED_TYPES + +These configurations are available in the [configs](/extras/configs) subdirectory. + +======================== +# Configurations of other libraries + +**TinyGPS** uses the **Nominal** configuration + a second `fix`. + +**TinyGPSPlus** uses the **Nominal** configuration + statistics + a second fix + timestamps for each `fix` member. + +**Adafruit_GPS** uses the **Nominal** configuration + geoid height and IGNORES CHECKSUM! diff --git a/software/firmware/libraries/NeoGPS/extras/doc/Data Model.md b/software/firmware/libraries/NeoGPS/extras/doc/Data Model.md new file mode 100644 index 0000000..03d6f90 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/doc/Data Model.md @@ -0,0 +1,253 @@ +Data Model +========== +Rather than holding onto individual fields, the concept of a **fix** is used to group data members of the GPS acquisition into a C structure (a `struct` type called `gps_fix`). This also facilitates merging pieces received at different times (i.e., in separate sentences) into a single easy-to-use structure. + +The main `NMEAGPS gps;` object you declare in your sketch parses received characters, gradually assembling a `fix`. Most programs will call `gps.read()` to obtain the completed fix structure (see [Usage](#Usage) below). + +Given a variable declaration of type `gps_fix`: +``` +gps_fix fix; +``` +...this `fix` variable (or any other variable of type `gps_fix`) contains the following members: + * `fix.status`, a status code + * `enum` values STATUS_NONE, STATUS_EST, STATUS_TIME_ONLY, STATUS_STD or STATUS_DGPS + * a [location](Location.md) structure (i.e., latitude and longitude), accessed with + * `fix.latitudeL()` and `fix.longitudeL()` for the higher-precision integer degrees, scaled by 10,000,000 (10 significant digits) + * `fix.latitude()` and `fix.longitude()` for the lower-precision floating-point degrees (~7 significant digits) + * NOTE: these lat/lon values are + * positive for North or East degrees and negative for South or West degrees. + * stored in a 'fix.location' structure, like a 2D coordinate. The `location_t` class provides additional methods for distance, bearing and offset calculations, as described [here](Location.md). + * `fix.latitudeDMS` and `fix.latitudeDMS` are structures (see DMS.h) that each contain + * `fix.longitudeDMS.degrees` in integer degrees + * `fix.latitudeDMS.degrees`, in integer minutes + * `fix.longitudeDMS.seconds_whole`, in integer seconds + * `fix.latitudeDMS.seconds_frac`, in integer thousandths of a second + * `fix.latitudeDMS.secondsF()`, in floating-point seconds + * hemisphere indicator, accessed with + * `fix.longitudeDMS.hemisphere` (enum values NORTH_H, SOUTH_H, EAST_H or WEST_H) + * `fix.longitudeDMS.EW()` (char values `E` or `W`) + * `fix.latitudeDMS.NS()` (char values `N` or `S`) + * NOTE: An integer degree value (scaled by 107 can be used to set the DMS structure by using `fix.latitudeDMS.From( otherLatitude );` + * an altitude (above ellipsoid, not Mean Sea Level), accessed with + * `fix.altitude_cm()`, in integer centimeters + * `fix.altitude()`, in floating-point meters + * `fix.alt.whole`, in integer meters + * `fix.alt.frac`, in integer centimeters, to be added to the whole part + * a speed, accessed with + * `fix.speed_kph()`, in floating-point kilometers per hour + * `fix.speed_mph()`, in floating-point miles per hour + * `fix.speed()`, in floating-point knots (nautical miles per hour) + * `fix.speed_mkn()`, in integer knots, scaled by 1000 + * `fix.spd.whole`, in integer knots + * `fix.spd.frac`, in integer thousandths of a knot, to be added to the whole part + * a heading, accessed with + * `fix.heading_cd()`, in integer hundredths of a degree + * `fix.heading()`, in floating-point degrees + * `fix.hdop`, `fix.vdop` and `fix.pdop`, in integer thousandths of the DOP. + * [Dilution of Precision](https://en.wikipedia.org/wiki/Dilution_of_precision_(navigation)) is a unitless measure of the current satellite constellation geometry WRT how 'good' it is for determining a position. This is _independent_ of signal strength and many other factors that may be internal to the receiver.   **It cannot be used to determine position accuracy in meters.** Instead, use the LAT/LON/ALT error in cm members, which are populated by GST sentences. + * latitude, longitude and altitude error, accessed with + * `fix.lat_err_cm`, `fix.lon_err_cm` and `fix.alt_err_cm`, in integer centimeters + * `fix.lat_err()`, `fix.lon_err()` and `fix.alt_err()`, in floating-point meters + * geoid height above ellipsoid (see [here](https://en.wikipedia.org/wiki/Geoid) for description), accessed with + * `fix.geoidHeight_cm`, in integer centimeters + * `fix.geoidHeight()`, in floating-point meters + * `fix.geoidHt.whole`, in integer meters + * `fix.geoidHt.frac`, in integer centimeters to be added to the whole part + * `fix.satellites`, a satellite count + * a date/time structure (see [Time.h](/src/Time.h)), accessed with + * `fix.dateTime.year`, + * `fix.dateTime.month`, + * `fix.dateTime.date`, the day-of-month, + * `fix.dateTime.hours`, + * `fix.dateTime.minutes`, + * `fix.dateTime.seconds`, and + * `fix.dateTime.day`, the day-of-the-week. This member is expensive to calculate, so it is *uninitialized* until you call the `set_day()` method. If you need the day-of-the-week, be sure to call `set_day` whenever the `year`, `month` or `date` members are changed. In general, call `fix.dateTime.set_day()` whenever `fix` is assigned (e.g., `fix = gps.read()`).

+ `Time` operations allow converting to and from total seconds offset from a *de facto* starting time (e.g., an epoch date/time "origin"). There are constants in Time.h for NTP, POSIX and Y2K epochs. Simply change the `static` members `s_epoch_year` and `s_epoch_weekday` in Time.h, and all date/time operations will be based on that epoch. This does not affect GPS times, but it will allow you to easily convert a GPS time to/from an NTP or POSIX time value (seconds).

+ The [NMEAtimezone.ino](/examples/NMEAtimezone/NMEAtimezone.ino) example program shows how to convert the GPS time (UTC) into a local time. Basically, a `Time` structure is converted to seconds (from the epoch start), then the time zone offset *in seconds* is added, and then the offset seconds are converted back to a time structure, with corrected day, month, year, hours and minutes members. + * `fix.dateTime_cs`, in integer hundredths of a second + * `fix.dateTime_ms()`, in milliseconds + * `fix.dateTime_us()`, in microseconds + * a collection of boolean `valid` flags for each of the above members, accessed with + * `fix.valid.status` + * `fix.valid.date` for year, month, day-of-month + * `fix.valid.time` for hours, minutes, seconds and centiseconds + * `fix.valid.location` for latitude and longitude + * `fix.valid.altitude` + * `fix.valid.speed` + * `fix.valid.heading` + * `fix.valid.hdop`, `fix.valid.vdop` and `fix.valid.hpop` + * `fix.valid.lat_err`, `fix.valid.lon_err` and `fix.valid.alt_err` + * `fix.valid.geoidHeight` + +## Validity +Because the GPS device may *not* have a fix, each member of a `gps_fix` can be marked as valid or invalid. That is, the GPS device may not know the lat/long yet. To check whether the fix member has been received, test the corresponding `valid` flag (described above). For example, to check if lat/long data has been received: +``` + if (my_fix.valid.location) { + Serial.print( my_fix.latitude() ); + Serial.print( ',' ); + Serial.println( my_fix.longitude() ); + } +``` +You should also know that, even though you have enabled a particular member (see [GPSfix_cfg.h](/src/GPSfix_cfg.h)), it **may not have a value** until the related NMEA sentence sets it. And if you have not enabled that sentence for parsing in `NMEAGPS_cfg.h`, it will **never** be valid. + +## Other GPS-related information +There is additional information that is not related to a fix. Instead, it contains information about parsing or a [**G**lobal **N**avigation **S**atellite **S**ystem](https://en.wikipedia.org/wiki/Satellite_navigation). GNSS's currently include GPS (US), GLONASS (Russia), Beidou (China) and Galileo (EU). The main `NMEAGPS gps` object you declare in your sketch contains: + * `gps.UTCsecondStart()`, the Arduino `micros()` value when the current UTC second started + * `gps.UTCms()`, the number of milliseconds since the last received UTC time, calculated from `micros()` and `gps.UTCsecondStart`. + * `gps.UTCus()`, the number of microseconds since the last received UTC time, calculated from `micros()` and `gps.UTCsecondStart`. + * `gps.nmeaMessage`, the latest received message type. This is an ephemeral value, because multiple sentences are merged into one `fix` structure. If you only check this after a complete fix is received, you will only see the LAST_SENTENCE_IN_INTERVAL. + * enum values NMEA_GLL, NMEA_GSA, NMEA_GST, NMEA_GSV, NMEA_RMC, NMEA_VTG or NMEA_ZDA + * `gps.satellies[]`, an array of satellite-specific information, where each element contains + * `gps.satellies[i].id`, satellite ID + * `gps.satellies[i].elevation`, satellite elevation in 0-90 integer degrees + * `gps.satellies[i].azimuth`, satellite azimuth in 0-359 integer degrees + * `gps.satellies[i].snr`, satellite signal-to-noise ratio in 0-99 integer dBHz + * `gps.satellies[i].tracked`, satellite being tracked flag, a boolean + * `gps.talker_id[]`, talker ID, a two-character array (not NUL-terminated) + * `gps.mfr_id[]`, manufacturer ID, a three-character array (not NUL-terminated) + * an internal fix structure, `gps.fix()`. Most sketches **should not** use `gps.fix()` directly! + +## Usage +First, declare an instance of `NMEAGPS`: +``` +NMEAGPS gps; +``` +Next, tell the `gps` object to handle any available characters on the serial port: +``` +void loop() +{ + while (gps.available( gps_port )) { +``` +The `gps` object will check if there are any characters available, and if so, read them from the port and parse them into its internal fix. Many characters will have to be read before the current fix is complete, so `gps.available` will return `false` until the fix is complete; the body of `while` loop will be skipped many times, and the rest of `loop()` will be executed. + +When a fix is finally completed, `gps.available` will return `true`. Now your sketch can "read" the completed fix structure from the `gps` object: +``` +void loop() +{ + while (gps.available( gps_port )) { + gps_fix fix = gps.read(); +``` +The local `fix` variable now contains all the GPS fields that were parsed from the `gps_port`. You can access them as described above: +``` +void loop() +{ + while (gps.available( gps_port )) { + gps_fix fix = gps.read(); + if (fix.valid.time) { + ... +``` +Note that the `fix` variable is local to that `while` loop; it cannot be accessed elsewhere in your sketch. If you need to access the fix information elsewhere, you must declare a global fix variable: +``` +gps_fix currentFix; + +void loop() +{ + while (gps.available( gps_port )) { + currentFix = gps.read(); + if (currentFix.valid.time) { + ... +``` +Any part of your sketch can use the information in `currentFix`. + +Please note that the fix structure is much smaller than the raw character data (sentences). A fix is nominally 1/4 the size of one sentence (~30 bytes vs ~120 bytes). If two sentences are sent during each update interval, a fix could be 1/8 the size required for buffering two sentences. + +In this fix-oriented program structure, the methods `gps.available` and `gps.read` are manipulating entire `gps_fix` structures. Multiple characters and sentences are used internally to fill out a single fix: members are "merged" from sentences into one fix structure (described [here](Merging.md)). + +That program structure is very similar to the typical serial port reading loop: +``` +void loop() +{ + while (serial.available()) { + char c = serial.read(); + ... do something with the character ...; + } +``` +However, the fix-oriented methods operate on complete *fixes*, not individual characters, fields or sentences. + +Note: If you find that you need to filter or merge data with a finer level of control, you may need to use a different [Merging option](Merging.md), [Coherency](Coherency.md), or the more-advanced [Character-Oriented methods](/doc/CharOriented.md). + +## Examples +Some examples of accessing fix values: +``` +gps_fix fix_copy = gps.read(); + +int32_t lat_10e7 = fix_copy.lat; // scaled integer value of latitude +float lat = fix_copy.latitude(); // float value of latitude + +Serial.print( fix_copy.latDMS.degrees ); +Serial.print( ' ' ); +Serial.print( fix_copy.latDMS.minutes ); +Serial.print( F("' " ); +Serial.print( fix_copy.latDMS.seconds ); + +if (fix_copy.dateTime.month == 4) // test for the cruelest month + cry(); + +// Count how satellites are being received for each GNSS +for (uint8_t i=0; i < gps.sat_count; i++) { + if (gps.satellites[i].tracked) { + if (gps.satellites[i] . id <= 32) + GPS_satellites++; + if (gps.satellites[i] . id <= 64) + SBAS_satellites++; + if (gps.satellites[i] . id <= 96) + GLONASS_satellites++; + } +} +``` + +And some examples of accessing valid flags in a `fix` structure: +``` +if (fix_copy.valid.location) + // we have a lat/long! + +if (fix_copy.valid.time) + // the copy has hours, minutes and seconds +``` +Here's an example for accessing the altitude +``` + if (fix_copy.valid.altitude) { + z2 = fix_copy.altitude_cm(); + vz = (z2 - z1) / dt; + z1 = z2; + + // Note: if you only care about meters, you could also do this: + // z = fix_copy.alt.whole; + } +``` +You can also check a collection of flags before performing a calculation involving +multiple members: +``` + if (fix_copy.valid.altitude && fix_copy.valid.date && fix_copy.valid.time) { + dt = (clock_t) fix_copy.dateTime - (clock_t) fix_copy.dateTime; + dz = fix_copy.alt.whole - last_alt; // meters + vz = dz / dt; // meters per second vertical velocity + } +``` +Bonus: The compiler will optimize this into a single bit mask operation. + +The example printing utility file, [Streamers.cpp](/src/Streamers.cpp#L100) shows how to access each fix member and print its value. + +## Options +Except for `status`, each of these `gps_fix` members is conditionally compiled; any, all, or *no* members can be selected for parsing, storing and merging. This allows you to configuring NeoGPS to use the minimum amount of RAM for the particular members of interest. See [Configurations](Configurations.md) for how to edit [GPSfix_cfg.h](/src/GPSfix_cfg.h) and [NMEAGPS_cfg.h](/src/NMEAGPS_cfg.h#L67), respectively. + +## Precision +Integers are used for all members, retaining full precision of the original data. +``` + gps_fix fix = gps.read(); + if (fix.valid.location) { + // 32-bit ints have 10 significant digits, so you can detect very + // small changes in position: + d_lat = fix_copy.lat - last_lat; + } +``` + +Optional floating-point accessors are provided for many members. +``` + if (fix_copy.valid.location) { + float lat = fix_copy.latitude(); + + // floats only have about 6 significant digits, so this + // computation is useless for detecting small movements: + foobar = (lat - target_lat); +``` diff --git a/software/firmware/libraries/NeoGPS/extras/doc/Examples.md b/software/firmware/libraries/NeoGPS/extras/doc/Examples.md new file mode 100644 index 0000000..83e406f --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/doc/Examples.md @@ -0,0 +1,168 @@ +Examples +====== +In an attempt to be reusable in a variety of different programming styles, this library supports: +* sync or async operation (main `loop()` vs interrupt processing) +* fused or not fused (multiple reports into one fix) +* optional buffering of fixes +* optional floating point +* configurable message sets, including hooks for implementing proprietary NMEA messages +* configurable message fields +* multiple protocols from same device + +These example programs demonstrate how to use the classes in the different programming styles: +* [NMEA](/examples/NMEA/NMEA.ino) - sync, single fix, standard NMEA only (RMC sentence only) +* [NMEA_isr](/examples/NMEA_isr/NMEA_isr.ino) - **async**, single fix, standard NMEA only (RMC sentence only) +* [NMEAblink](/examples/NMEAblink/NMEAblink.ino) - sync, single fix, standard NMEA only, minimal example, only blinks LED +* [NMEAloc](/examples/NMEAloc/NMEAloc.ino) - sync, single fix, minimal example using only standard NMEA RMC sentence +* [NMEAlocDMS](/examples/NMEAlocDMS/NMEAlocDMS.ino) - same as NMEAloc.ino, but displays location in Degrees, Minutes and Seconds +* [NMEAaverage](/examples/NMEAaverage/NMEAaverage.ino) - sync, single fix, averages a high-accuracy location over time +* [NMEAtimezone](/examples/NMEAtimezone/NMEAtimezone.ino) - same as NMEAloc.ino, but displays local time instead of UTC (GMT) +* [NMEASDlog](/examples/NMEASDlog/NMEASDlog.ino) - **async**, buffered fixes, standard NMEA only (RMC sentence only), logging to SD card +* [PUBX](/examples/PUBX/PUBX.ino) - sync, coherent fix, standard NMEA + ublox proprietary NMEA +* [ublox](/examples/ublox/ublox.ino) - sync or **async**, coherent fix, ublox binary protocol UBX + +Preprocessor symbol `USE_FLOAT` can be used in [Streamers.cpp](/src/Streamers.cpp) to select integer or floating-point output. + +See also important information in `NMEAorder.ino` below, and the [Installing](Installing.md), [Configurations](Configurations.md) and [Troubleshooting](Troubleshooting.md) sections. + +##Diagnostics +Several programs are provided to help diagnose GPS device problems: + +### Connection and Baud Rate + +* [NMEAdiagnostic](/examples/NMEAdiagnostic/NMEAdiagnostic.ino) + +This program listens for sentences and, if none are detected, tries a different baud rate. When sentences are detected, the correct baud rate is displayed. The received data may help you determine the problem (e.g., dropped characters or binary protocol). + +See the [Troubleshooting](Troubleshooting.md) section for more details. + +### Sentence order + +* [NMEAorder](/examples/NMEAorder/NMEAorder.ino) + +This program determines the order of NMEA sentences sent during each 1-second interval: + +``` +NMEAorder.INO: started +fix object size = 44 +NMEAGPS object size = 72 +Looking for GPS device on Serial1 +..................... +Sentence order in each 1-second interval: + RMC + VTG + GGA + GSA + GSV + GSV + GSV + GSV + GLL +``` + +The last sentence is of particular interest, as it is used to determine when the quiet time begins. All example programs **depend** on knowing the last sentence (see [Quiet Time Interval](Troubleshooting#quiet-time-interval)). + +### Self-test Program + +* [NMEAtest](/examples/NMEAtest/NMEAtest.ino) + +For this program, **No GPS device is required**. Test bytes are streamed from PROGMEM character arrays. Various strings are passed to `decode` and the expected pass or fail results are displayed. If **NeoGPS** is correctly configured, you should see this on your SerialMonitor: + +``` +NMEA test: started +fix object size = 44 +NMEAGPS object size = 72 +Test string length = 75 +PASSED 11 tests. +------ Samples ------ +Results format: + Status,UTC Date/Time,Lat,Lon,Hdg,Spd,Alt,HDOP,VDOP,PDOP,Lat err,Lon err,Alt err,Sats,[sat], + +Input: $GPGGA,092725.00,4717.11399,N,00833.91590,E,1,8,1.01,499.6,M,48.0,M,,0*5B +Results: 3,2000-01-01 09:27:25.00,472852332,85652650,,,49960,1010,,,,,,8,[], + +Input: $GPRMC,092725.00,A,2520.69213,S,13101.94948,E,0.004,77.52,091202,,,A*43 +Results: 3,2002-12-09 09:27:25.00,-253448688,1310324913,7752,4,,,,,,,,,[], + +Input: $GPRMC,162254.00,A,3647.6643,N,8957.5193,W,0.820,188.36,110706,,,A*49 +Results: 3,2006-07-11 16:22:54.00,367944050,-899586550,18836,820,,,,,,,,,[], + +Input: $GPRMC,235959.99,A,2149.65726,N,16014.69256,W,8.690,359.99,051015,9.47,E,A*26 +Results: 3,2015-10-05 23:59:59.99,218276210,-1602448760,35999,8690,,,,,,,,,[], + +Input: $GNGLL,0105.60764,S,03701.70233,E,225627.00,A,A*6B +Results: 3,2000-01-01 22:56:27.00,-10934607,370283722,,,,,,,,,,,[], + +Input: $GPGGA,064951.000,2307.1256,N,12016.4438,E,1,8,0.95,39.9,M,17.8,M,,*63 +Results: 3,2000-01-01 06:49:51.00,231187600,1202740633,,,3990,950,,,,,,8,[], + +Input: $GPRMC,064951.000,A,2307.1256,N,12016.4438,E,0.03,165.48,260406,3.05,W,A*2C +Results: 3,2006-04-26 06:49:51.00,231187600,1202740633,16548,30,,,,,,,,,[], + +Input: $GPVTG,165.48,T,,M,0.03,N,0.06,K,A*36 +Results: 3,,,,16548,30,,,,,,,,,[], + +Input: $GPGSA,A,3,29,21,26,15,18,09,06,10,,,,,2.32,0.95,2.11*00 +Results: 3,,,,,,,950,,2320,,,,,[], + +Input: $GPGSV,3,1,09,29,36,029,42,21,46,314,43,26,44,020,43,15,21,321,39*7D +Results: ,,,,,,,,,,,,,9,[29,21,26,15,], + +Input: $GPGSV,3,2,09,18,26,314,40,09,57,170,44,06,20,229,37,10,26,084,37*77 +Results: ,,,,,,,,,,,,,9,[29,21,26,15,18,9,6,10,], + +Input: $GPGSV,3,3,09,07,,,26*73 +Results: ,,,,,,,,,,,,,9,[29,21,26,15,18,9,6,10,7,], + +Input: $GNGST,082356.00,1.8,,,,1.7,1.3,2.2*60 +Results: ,2000-01-01 08:23:56.00,,,,,,,,,170,130,,,[29,21,26,15,18,9,6,10,7,], + +Input: $GNRMC,083559.00,A,4717.11437,N,00833.91522,E,0.004,77.52,091202,,,A,V*33 +Results: 3,2002-12-09 08:35:59.00,472852395,85652537,7752,4,,,,,,,,,[29,21,26,15,18,9,6,10,7,], + +Input: $GNGGA,092725.00,4717.11399,N,00833.91590,E,1,08,1.01,499.6,M,48.0,M,,*45 +Results: 3,2000-01-01 09:27:25.00,472852332,85652650,,,49960,1010,,,,,,8,[29,21,26,15,18,9,6,10,7,], + +Input: $GLZDA,225627.00,21,09,2015,00,00*70 +Results: ,2015-09-21 22:56:27.00,,,,,,,,,,,,,[29,21,26,15,18,9,6,10,7,], + +--- floating point conversion tests --- + +Input: $GPGGA,092725.00,3242.9000,N,11705.8169,W,1,8,1.01,499.6,M,48.0,M,,0*49 +Results: 3,2000-01-01 09:27:25.00,327150000,-1170969483,,,49960,1010,,,,,,8,[29,21,26,15,18,9,6,10,7,], + +Input: $GPGGA,092725.00,3242.9000,N,11705.8170,W,1,8,1.01,499.6,M,48.0,M,,0*41 +Results: 3,2000-01-01 09:27:25.00,327150000,-1170969500,,,49960,1010,,,,,,8,[29,21,26,15,18,9,6,10,7,], + +Input: $GPGGA,092725.00,3242.9000,N,11705.8171,W,1,8,1.01,499.6,M,48.0,M,,0*40 +Results: 3,2000-01-01 09:27:25.00,327150000,-1170969517,,,49960,1010,,,,,,8,[29,21,26,15,18,9,6,10,7,], + +Input: $GPGGA,092725.00,3242.9000,N,11705.8172,W,1,8,1.01,499.6,M,48.0,M,,0*43 +Results: 3,2000-01-01 09:27:25.00,327150000,-1170969533,,,49960,1010,,,,,,8,[29,21,26,15,18,9,6,10,7,], + +Input: $GPGGA,092725.00,3242.9000,N,11705.8173,W,1,8,1.01,499.6,M,48.0,M,,0*42 +Results: 3,2000-01-01 09:27:25.00,327150000,-1170969550,,,49960,1010,,,,,,8,[29,21,26,15,18,9,6,10,7,], + +Input: $GPGGA,092725.00,3242.9000,N,11705.8174,W,1,8,1.01,499.6,M,48.0,M,,0*45 +Results: 3,2000-01-01 09:27:25.00,327150000,-1170969567,,,49960,1010,,,,,,8,[29,21,26,15,18,9,6,10,7,], + +Input: $GPGGA,092725.00,3242.9000,N,11705.8175,W,1,8,1.01,499.6,M,48.0,M,,0*44 +Results: 3,2000-01-01 09:27:25.00,327150000,-1170969583,,,49960,1010,,,,,,8,[29,21,26,15,18,9,6,10,7,], + +Input: $GPGGA,092725.00,3242.9000,N,11705.8176,W,1,8,1.01,499.6,M,48.0,M,,0*47 +Results: 3,2000-01-01 09:27:25.00,327150000,-1170969600,,,49960,1010,,,,,,8,[29,21,26,15,18,9,6,10,7,], +``` + +### Benchmark + +* [NMEAbenchmark](/examples/NMEAbenchmark/NMEAbenchmark.ino) + +For this program, **No GPS device is required**. GGA, RMC and GSV sentences can be tested. Bytes are streamed from PROGMEM character arrays and parsed to determine execution times. All times are displayed in microseconds: + +``` +NMEAbenchmark: started +fix object size = 22 +NMEAGPS object size = 29 +GGA time = 844 +GGA no lat time = 497 +``` diff --git a/software/firmware/libraries/NeoGPS/extras/doc/Extending.md b/software/firmware/libraries/NeoGPS/extras/doc/Extending.md new file mode 100644 index 0000000..8f4b917 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/doc/Extending.md @@ -0,0 +1,50 @@ +Extending NeoGPS +========= +Using features that are unique to your device fall into three categories: +####1. Configuring the device with special commands +Many devices allow you to configure which standard messages are emitted, or the rate at which they are emitted. It may be as simple as sending a proprietary command to the device. Simply use the NMEAGPS `send` or `send_P` method. + +For example, to set the baudrate of the ublox NEO-6M gps device, send it a +`UBX,41` message: +``` + gps.send_P( F("PUBX,41,1,0007,0003,19200,0") ); +``` +####2. Parsing additional message types +Some devices provide additional messages with extra information, or more efficient groupings. This will require deriving a class from `NMEAGPS`. The derived class needs to +* declare a PROGMEM table of the new message types, +* point that table back to the NMEAGPS table +* override the `parseField` method to extract information from each new message type + +Please see ubxNMEA.h and .cpp for an example of adding two ublox-proprietary messages. + +####3. Handling new protocols +Some devices provide additional protocols. They are frequently binary, which requires +fewer bytes than NMEA 0183. Because they can both be transmitted on the same port, it is +very likely that they can be distinguished at the message framing level. + +For example, NMEA messages always start with a '$' and end with CR/LF. ublox messages start +with 0xB5 and 0x62 bytes, a message class and id, and a 2-byte message length. There is no +terminating character; the message completed when `length` bytes have been received. + +This will require deriving a class from `NMEAGPS`. The derived class needs +to +* define new `rxState` values for the protocol state machine. These should +be unique from the NMEA state values, but they should share the IDLE state +value. +* override the `decode` method to watch for its messages. As bytes are +received, it may transition out of the IDLE state and into its own set of +state values. If the character is not valid for this protocol, it should +delegate it to the NMEAGPS base clase, which may begin processing an NMEAGPS +message. If the rxState is not one of the derived states (i.e., it is in +one of the NMEAGPS states), the character should be delegated to +NMEAGPS::decode. +* implement something like the `parseField` method if parse-in-place +behavior is desirable. This is not necessarily `virtual`, as it will only +be called from the derived `decode`. +* You are free to add methods and data members as required for handling the +protocol. Only `decode` must be overridden. + +Please see ubxGPS.h and .cpp for an example of implementing the +ublox-proprietary protocol, UBX. The derived `ubloxGPS` class provides both +parse-in-place *and* buffered messages. See the `send` and `poll` methods. + diff --git a/software/firmware/libraries/NeoGPS/extras/doc/Installing.md b/software/firmware/libraries/NeoGPS/extras/doc/Installing.md new file mode 100644 index 0000000..48bb5db --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/doc/Installing.md @@ -0,0 +1,196 @@ +Installing +========== + +1. [Download the library](#1-download-the-library) +2. [Choose a serial port](#2-choose-a-serial-port) +3. [Connect the GPS device](#3-connect-the-gps-device) +4. [Review `GPSport.h`](#4-review-librariesneogpssrcgpsporth) +5. [Open the example](#5--open-the-example-sketch-nmeaino) +6. [Build and upload](#6--build-and-upload-the-sketch-to-your-arduino) +
+ +### 1. Download the library + +It is easiest to use the [Ardino IDE Library Manager](https://www.arduino.cc/en/Guide/Libraries#toc3) to automatically download and install NeoGPS. Select the menu **Sketch -> Include Library -> Manage Libraries**. Then type "NeoGPS" in the Search box. + +If you need to perform a manual installation,: + +* Download the [master ZIP file](https://github.com/SlashDevin/NeoGPS/archive/master.zip). +* Open the zip file and open the nested `NeoGPS-master` subdirectory. +* Select and copy all files in the `NeoGPS-master` subdirectory into a new `Arduino/Libraries/NeoGPS` directory, like most libraries. The `Arduino/Libraries/NeoGPS` directory should contain:
+``` +extras +examples +src +library.properties +LICENSE +README.md +``` + +
+ +### 2. Choose a serial port + +**BEST**: The fastest, most reliable way to connect a GPS device is to use a HardwareSerial port. + +On any Arduino board, you can connect the GPS device to the `Serial` pins (0 & 1). You can still print debug statements, and they will show up on the Serial Monitor window. The received GPS characters will not interfere with those prints, and you will not see those characters on the Serial Monitor window. + +However, when you need to upload a new sketch to the Arduino over USB, **you must disconnect the GPS TX from the Arduino RX pin 0.** Otherwise, the GPS characters will interfere with the upload data. Some people put a switch in that connection to make it easy to upload without disturbing the wires. + +For Mega, Due and Teensy boards, you can connect the GPS device to the `Serial1`, `Serial2` or `Serial3` pins. + +For Micro and Leo (and other 32U4-based Arduinos), you can connect the GPS device to the `Serial1` pins. + +**2nd Best**: If you can't connect the GPS device to a `HardwareSerial` port, you should download and install the [AltSoftSerial](https://github.com/PaulStoffregen/AltSoftSerial) or [NeoICSerial](https://github.com/SlashDevin/NeoICSerial) library. These libraries only work on two specific pins (8 & 9 on an UNO). This library is very efficient and reliable. It uses one of the hardware TIMERs, so it may conflict with libraries that use TIMERs or PWM output (e.g., servo). + +**3rd Best**: If you can't use the pins required by `AltSoftSerial`, and your GPS device runs at 9600, 19200 or 38400 baud, you should download and install the [NeoSWSerial](https://github.com/SlashDevin/NeoSWSerial) library. This library is almost as efficient. It will help you avoid common timing problems caused by `SoftwareSerial`. It does not need an extra TIMER, so it can be used with most other libraries. It does use Pin Change Interrupts, but there is an option in the header file that allows you to coordinate other PCI usage with `NeoSWSerial`. + +`NeoSWSerial` can be used with `AltSoftSerial` at the same time, allowing your sketch to have two extra serial ports. + +**WORST**: `SoftwareSerial` is NOT RECOMMENDED, because it disables interrupts for long periods of time. This can interfere with other parts of your sketch, or with other libraries. It cannot transmit and receive at the same time, and your sketch can only receive from one `SoftwareSerial` instance at time. + +
+ +### 3. Connect the GPS device + +Most GPS devices are 3.3V devices, and most Arduinos are 5V devices. Although many GPS modules are described as "3V & 5V compatible", + +

YOU SHOULD NOT CONNECT A 5V ARDUINO TRANSMIT PIN TO THE 3.3V GPS RX PIN

+ +This can damage the device, cause overheating, system power problems or decrease the lifetime of battery-operated systems. You must level-shift this connection with inexpensive level-shifting modules (best) or a resistor divider. + +Connecting the 3.3V GPS TX pin to a 5V Arduino receive pin will not damage the GPS device, but it may not be reliable. This is because the GPS TX voltage is slightly lower than what the Arduino requires. It works in many situations, but if you are not able to receive GPS characters reliably, you probably need to use a level-shifting module (best) or a diode+resistor to "pull up" the GPS TX pin voltage. + +
+ +### 4. Review `Libraries/NeoGPS/src/GPSport.h` + +This file declares a the serial port to be used for the GPS device. You can either: + +* Use the default `GPSport.h` and connect your GPS device according to what it chooses; or +* Replace the entire contents of `GPSport.h` and insert your own declarations (see below and comments in `GPSport.h`). + +#### Default choices for GPSport.h + +By default, Mega, Leonardo, Due, Zero/MKR1000 and Teensy boards will use `Serial1`. + +All other Boards will use [AltSoftSerial](https://github.com/PaulStoffregen/AltSoftSerial) on two specific pins (see table at linked page). + +If you want to use a different serial port library (review step 2 above), you must edit these `#include` lines in `GPSport.h`: + +``` + //#include // NeoSerial or NeoSerial1 for INTERRUPT_PROCESSING + #include // <-- DEFAULT. Two specific pins required (see docs) + //#include // AltSoftSerial with Interrupt-style processing + //#include // Any pins, only @ 9600, 19200 or 38400 baud + //#include // NOT RECOMMENDED! +``` + +Uncomment **one** of those include statements, and it will use that library for the GPS serial port. + +If you uncomment the `NeoSWSerial.h` include, pins 3 and 4 will be used for the GPS. If your GPS is on different pins, you must edit these `#define` lines in `GPSport.h`: + + #define RX_PIN 4 + #define TX_PIN 3 + + + +#### Choosing your own serial port + +If you know what serial port you want to use, you can **REPLACE EVERYTHING** in `GPSport.h' with the three declarations that are used by all example programs: + +1. the `gpsPort` variable **(include its library header if needed)**; +2. the double-quoted C string for the `GPS_PORT_NAME` (displayed by all example programs); and +3. the `DEBUG_PORT` to use for Serial Monitor print messages (usually `Serial`). + +All the example programs can use any of the following serial port types: + +* HardwareSerial (built-in `Serial`, `Serial1` et al. STRONGLY recommended) +* [AltSoftSerial](https://github.com/PaulStoffregen/AltSoftSerial) **DEFAULT** (only works on one specific Input Capture pin) +* [NeoICSerial](https://github.com/SlashDevin/NeoICSerial) (only works on one specific Input Capture pin) +* [NeoHWSerial](https://github.com/SlashDevin/NeoHWSerial) (required for NMEA_isr and NMEASDlog on built-in serial ports) +* [NeoSWSerial](https://github.com/SlashDevin/NeoSWSerial) (works on most pins) +* SoftwareSerial (built-in, NOT recommended) + +Be sure to download the library you have selected (NOTE: `HardwareSerial` and `SoftwareSerial` are pre-installed by the Arduino IDE and do not need to be downloaded). + +For example, to make all examples use `Serial` for the GPS port **and** for Serial Monitor messages, `GPSport.h` should contain just these 3 declarations: + +``` +#ifndef GPSport_h +#define GPSport_h + +#define gpsPort Serial +#define GPS_PORT_NAME "Serial" +#define DEBUG_PORT Serial + +#endif +``` + +Or, to make all examples use `AltSoftSerial` for the GPS port and `Serial` for Serial Monitor messages, `GPSport.h` should contain just these statements: + +``` +#ifndef GPSport_h +#define GPSport_h + +#include +AltSoftSerial gpsPort; +#define GPS_PORT_NAME "AltSoftSerial" +#define DEBUG_PORT Serial + +#endif +``` + +
+ +### 5. Open the example sketch NMEA.ino + +In the Arduino IDE, select **File -> Examples -> NeoGPS -> NMEA**. + +
+ +### 6. Build and upload the sketch to your Arduino. + +**Note:** If the sketch does not compile, please see the [Troubleshooting](Troubleshooting.md#configuration-errors) section. + +When the sketch begins, you should see this: +``` +NMEA.INO: started + fix object size = 31 + gps object size = 84 +Looking for GPS device on Serial1 + +GPS quiet time is assumed to begin after a RMC sentence is received. + You should confirm this with NMEAorder.ino + +Status,UTC Date/Time,Lat,Lon,Hdg,Spd,Alt,Sats,Rx ok,Rx err,Rx chars, +3,2016-05-24 01:21:29.00,472852332,85652650,,138,,,1,0,66, +3,2016-05-24 01:21:30.00,472852311,85652653,,220,24040,7,9,0,557, +3,2016-05-24 01:21:31.00,472852315,85652647,,449,24080,7,17,0,1048, + etc. +``` +The default NeoGPS configuration is **Nominal**, as described [here](Configurations.md#typical-configurations). If you do not see this output, please review the [Troubleshooting](Troubleshooting.md#gps-device-connection-problems) section. + +This output can be copy & pasted into a into a text editor for saving as a CSV file, which can then be imported into a spreadsheet program for graphing or analysis. + + + +
+ +### The NMEA.ino example works! +Once you have verified the GPS device connection and build process with this first example, you should also verify your device's behavior with `NMEAorder.ino` (see [this section](Troubleshooting.md#quiet-time-interval)). This can avoid problems later on, when you start adding/merging other functions to do your "work". + +[Other examples](Examples.md) include `NMEAloc.ino`, which shows how to use just the location fields of a fix, or `NMEAtimezone.ino`, which shows how to adjust the GPS time for your local time zone. + +If you are logging information to an SD card, you should next try `NMEA_isr.ino`. It is identical to `NMEA.ino`, except that it handles the GPS characters during the RX char interrupt. Interrupt handling will require one of the NeoXXSerial libraries to be installed (e.g. [NeoHWSerial](https://github.com/SlashDevin/NeoHWSerial)). + +If you are working on a drone or other autonomous system, you should you should read about [Coherency](Coherency.md) and the interrupt-driven technique in [NMEA_isr](/examples/NMEA_isr/NMEA_isr.ino). + +You can also try other configurations. Please see [Choosing Your Configuration](Choosing.md) for more information, and then simply edit `GPSfix_cfg.h` and/or `NMEAGPS_cfg.h`, or select an [example configuration](../configs) and copy these three files into your application directory: `NeoGPS_cfg.h`, `GPSfix_cfg.h`, and `NMEAGPS_cfg.h`. + +You can review and edit each of the copied configuration files to add or remove messages or fields, at any time. + +**Note:** Not all configurations will work with all example applications. Compiler error messages are emitted for incompatible settings, or if an example requires certain configurations. + +### I have a ublox GPS device +After you have tried all the standard NMEA examples, and you need the ublox-specific capabilities of NeoGPS, please see the [ublox](ublox.md) section. Try `PUBX.ino` first, then try `ublox.ino` if you *really* need the binary protocol. diff --git a/software/firmware/libraries/NeoGPS/extras/doc/License.md b/software/firmware/libraries/NeoGPS/extras/doc/License.md new file mode 100644 index 0000000..0cd7f34 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/doc/License.md @@ -0,0 +1,18 @@ +### License: + +**NeoGPS** + +Copyright (C) 2014-2017, SlashDevin + +NeoGPS is free software: you can redistribute it and/or modify +it under the terms of the GNU General Public License as published by +the Free Software Foundation, either version 3 of the License, or +(at your option) any later version. + +NeoGPS is distributed in the hope that it will be useful, +but WITHOUT ANY WARRANTY; without even the implied warranty of +MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +GNU General Public License for more details. + +You should have received a copy of the GNU General Public License +along with NeoGPS. If not, see . diff --git a/software/firmware/libraries/NeoGPS/extras/doc/Location.md b/software/firmware/libraries/NeoGPS/extras/doc/Location.md new file mode 100644 index 0000000..bbea5c2 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/doc/Location.md @@ -0,0 +1,62 @@ +Location +======== +The `Location_t` class is a 2D point, containing a latitude and longitude in integer degrees * 107 (source [here](/src/Location.h)). + +This class also provides geographic distance, bearing and offset functions. Furthermore, they all take advantage of the increased precision of the integer coordinates. Other libraries use floating-point coordinates, which have only 6 or 7 significant digits. By using integer math, calculations maintain their original accuracy as long as possible. For example, small distances can be calculated to millimeter accuracy. + +The example program [NMEAaverage.ino](/examples/NMEAaverage/NMEAaverage.ino) shows several techniques for performing 2D calculations. + +### Distance + +To calculate the distance between a pre-determined point and the current fix, + +``` +NeoGPS::Location_t madrid( 404381311L, -38196229L ); // see https://www.google.com/maps/@40.4381311,-3.8196229,6z +gps_fix fix; + +void loop() +{ + while (gps.available( gps_port )) { + fix = gps.read(); + float dist = fix.location.DistanceKm( madrid ); + // or dist = NeoGPS::Location_t::DistanceKm( fix.location, madrid ); + Serial.print( dist ); + Serial.println( F(" km") ); +``` + +`DistanceMiles` is also available + +### Bearing + +To calculate the bearing from one point to another (in radians, CW from North), + +``` + float bearing = fix.location.BearingToDegrees( madrid ); + // or bearing = NeoGPS::Location_t::BearingToDegrees( fix.location, madrid ); +``` +Radians is returned by `BearingTo`. + +### Offsetting a Location + +To move a location by a specified distance, in a specified direction, + +``` + float bearing = fix.location.BearingToDegrees( madrid ); + // or bearing = NeoGPS::Location_t::BearingToDegrees( fix.location, madrid ); + + // Step 10km closer to the destination + Location_t next_stop( fix.location ); + next_stop.OffsetBy( bearing, 10 / NeoGPS::Location_t::EARTH_RADIUS_KM ); +``` +Notice that the distance is specified in *radians*. To convert from km to radians, divide by the Earth's radius in km. To convert from miles, divide the miles by the Earth's radius in miles. + +### NeoGPS namespace +Because the `Location_t` is inside the `NeoGPS` namespace, any time you want to declare your own instance, use any of the constants in that class (anything that requires the `Location_t` name), you must prefix it with `NeoGPS::` (shown above). As with any C++ namespace, you can relax that requirement by putting this statement anywhere after the NeoGPS includes: + +``` +using namespace NeoGPS; +``` + +This technique is used in the **NMEAaverage.ino** sketch. + +However, if you have any other libraries that declare their own `Location_t` (not likely), you could not use the `using` statement. `Time_t` is inside the `NeoGPS` namespace for the same reason: avoiding name collisions. diff --git a/software/firmware/libraries/NeoGPS/extras/doc/Merging.md b/software/firmware/libraries/NeoGPS/extras/doc/Merging.md new file mode 100644 index 0000000..ac1cb9b --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/doc/Merging.md @@ -0,0 +1,90 @@ +Merging +=========== +Because different NMEA sentences contain different pieces of a fix, they have to be "merged" to determine a complete picture. Some sentences contain only date and time. Others contain location and altitude, but not speed and heading (see table [here](Choosing.md)). + +There are several ways to use the GPS fix data: without merging, implicit merging, and **explicit merging ([the default](#3-explicit-merging))**. NeoGPS allows you to choose how you want multiple sentences to be merged: + +### 1. NO MERGING + +In this mode, `gps.read()` will return a fix that is populated from just one sentence. You will probably receive multiple sentences per update interval, depending on your GPS device. + +If you are interested in just a few pieces of information, and those pieces can be obtained from one or two sentences, you can wait for that specific sentence to arrive, and then use one or more members of the fix at that time. Make sure that "no merging" is selected in NMEAGPS_cfg.h by commenting out these lines: +``` +//#define NMEAGPS_EXPLICIT_MERGING +//#define NMEAGPS_IMPLICIT_MERGING +``` +Then write your loop to wait for the specific sentence: +``` +void loop() +{ + while (gps.available( gps_port )) { + const gps_fix & rmc = gps.read(); + + if (gps.nmeaMessage == NMEAGPS::NMEA_RMC) { + // All GPS-related work is performed inside this if statement + + if (rmc.valid.speed && (rmc.speed <= 5)) + Serial.println( F("Too slow!") ); + + if (rmc.valid.location && ... or any rmc member + } + } + + // Can't access rmc out here... +``` +If you are interested in pieces of information that are grouped by some detailed criteria (e.g., field values), you must select "no merging" and then manually merge the fixes of interest. The `merged` copy will be safe to access at any time: +``` +gps_fix merged; + +void loop() +{ + while (gps.available( gps_port )) { + const gps_fix & fix = gps.read(); + + if ((gps.nmeaMessage == NMEAGPS::NMEA_RMC) && + (fix.valid.heading && + ((4500 <= fix.heading_cd()) && (fix.heading_cd() < 9000)))){ + + merged |= fix; + + if (merged.valid.satellites && (rmc.satellites > 5)) + Serial.println( F("Moar sats!") ); + } + } + + // Can't access 'fix' out here, but 'merged' can be used... +``` +### 2. IMPLICIT MERGING +If you are interested in more pieces of information, perhaps requiring more kinds of sentences to be decoded, but don't really care about what time the pieces were received, you could enable implicit merging: +``` +//#define NMEAGPS_EXPLICIT_MERGING +#define NMEAGPS_IMPLICIT_MERGING +``` +As sentences are received, they are accumulated internally. Previous field values are retained until they are overwritten by another sentence. When `gps.available`, the accumulated fix can be obtained with `gps.read()`. + +Note: The members in an implicitly-merged fix may not be coherent (see [Coherency](Coherency.md). Also, checksum errors can cause the internal fix to be completely reset. Be sure your sketch checks the [valid flags](Data%20Model.md#validity) before using any fix data. + +### 3. EXPLICIT MERGING +This is the default setting. To enable explicit merging, make sure this is in NMEAGPS_cfg.h: +``` +#define NMEAGPS_EXPLICIT_MERGING +//#define NMEAGPS_IMPLICIT_MERGING + +#define NMEAGPS_FIX_MAX 1 +``` +NMEAGPS_FIX_MAX must be at least one to use EXPLICIT merging. + +As sentences are received, they are merged internally. When the LAST_SENTENCE_IN_INTERVAL is received, the internal fix is marked as "available", and it can be accessed by calling `gps.read()`. When the next sentence arrives, the internal fix structure will be emptied. + +``` +gps_fix_t currentFix; + +void loop() +{ + while (gps.available( gps_port )) + currentFix = gps.read(); + + check_position( currentFix ); +``` + +Explicit merging is also required to implement [Coherency](Coherency.md). diff --git a/software/firmware/libraries/NeoGPS/extras/doc/Performance.md b/software/firmware/libraries/NeoGPS/extras/doc/Performance.md new file mode 100644 index 0000000..e44d818 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/doc/Performance.md @@ -0,0 +1,48 @@ +Performance +=========== + +#### **NeoGPS** is **40% to 70% faster**. + +For comparison, the following sentences were parsed by various [Configurations](/doc/Configurations.md) of **NeoGPS**, **TinyGPS** and **TinyGPSPlus** on a 16MHz Arduino Mega2560. + +``` +$GPGGA,092725.00,4717.11399,N,00833.91590,E,1,8,1.01,499.6,M,48.0,M,,0*5B +$GPRMC,083559.00,A,4717.11437,N,00833.91522,E,0.004,77.52,091202,,,A*57 +$GPGSV,3,1,10,23,38,230,44,29,71,156,47,07,29,116,41,08,09,081,36*7F +$GPGSV,3,2,10,10,07,189,,05,05,220,,09,34,274,42,18,25,309,44*72 +$GPGSV,3,3,10,26,82,187,47,28,43,056,46*77 +``` + + + + + + + +
ConfigurationSentenceNeoGPSTinyGPS
Time (% faster)
TinyGPS++
Time (% faster)
Adafrut_GPS
Time (%faster)
MinimalGGA
RMC
329us
335us
- (78%)
- (77%)
- (78%)
- (77%)
DTLGGA
RMC
780us
803us
- (46%)
- (44%)
- (47%)
- (44%)
NominalGGA
RMC
864us
883us
1448us (40%)
1435us (39%)
1473us (41%)
1442us (39%)
1358us (36%)
1535us (42%)
FullGGA
RMC
GSV
908us
899us
2194us
- (37%)
- (37%)
- (-)
1523us (40%)
1560us (42%)
6651us (67%)
+ +#### Why is **NeoGPS** faster? + +Most libraries use extra buffers to accumulate parts of the sentence so they +can be parsed all at once. For example, an extra field buffer may hold on +to all the characters between commas. That buffer is then parsed into a +single data item, like `heading`. Some libraries even hold on to the +*entire* sentence before attempting to parse it. In addition to increasing +the RAM requirements, this requires **extra CPU time** to copy the bytes and +index through them... again. + +**NeoGPS** parses each character immediately into the data item. When the +delimiting comma is received, the data item has been fully computed *in +place* and is marked as valid. + +Most libraries parse all fields of their selected sentences. Although most +people use GPS for obtaining lat/long, some need only time, or even just one +pulse-per-second. + +**NeoGPS** configures each item separately. Disabled items are +conditionally compiled, which means they will not use any RAM, program space +or CPU time. The characters from those fields are simply skipped; they are +never copied into a buffer or processed. + +While it is significantly faster and smaller than all NMEA parsers, these same improvements also make +NeoGPS faster and smaller than _binary_ parsers. diff --git a/software/firmware/libraries/NeoGPS/extras/doc/Program.md b/software/firmware/libraries/NeoGPS/extras/doc/Program.md new file mode 100644 index 0000000..e49e79c --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/doc/Program.md @@ -0,0 +1,13 @@ +Program Space requirements +======= + +The **Minimal** configuration requires 866 bytes. + +The **DTL** configuration requires 2072 bytes. + +The **Nominal** configuration requires 2800 bytes. TinyGPS uses about 2400 bytes. TinyGPS++ uses about 2700 bytes. + +The **Full** configuration requires 3462 bytes. + +(All configuration numbers include 166 bytes PROGMEM.) + diff --git a/software/firmware/libraries/NeoGPS/extras/doc/RAM.md b/software/firmware/libraries/NeoGPS/extras/doc/RAM.md new file mode 100644 index 0000000..9043007 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/doc/RAM.md @@ -0,0 +1,41 @@ +RAM requirements +======= + +#### **NeoGPS** requires **72% to 96% _less_ RAM, saving 140 to 1100 bytes.** + +Because you can select what data members are stored, the RAM savings depends on the [configuration](Configurations.md): + + + + + + + +
ConfigurationNeoGPS
Size
TinyGPS
Size (% smaller)
TinyGPS++
Size (% smaller)
Adafruit_GPS
Size (% smaller)
Minimal10- (95%)- (96%)
DTL25- (86%)- (90%)
Nominal41180 (72%)240 (83%)326 (87%)
Full242- (-)~1400 (83%)
+ +#### Why does **NeoGPS** use less RAM? + +As data is received from the device, various portions of a `fix` are +modified. In fact, _**no buffering RAM is required**_. Each character +affects the internal state machine and may also contribute to a data member +(e.g., latitude). + +If your application only requires an accurate one pulse-per-second, you +can configure it to parse *no* sentence types and retain *no* data members. +This is the **Minimal** configuration. Although the +`fix().status` can be checked, no valid flags are available. Even +though no sentences are parsed and no data members are stored, the +application will still receive an empty `fix` once per second: + +``` +while (gps.available( gpsPort )) { + gps_fix nothingButStatus = gps.read(); + sentenceReceived(); +} +``` + +The `ubloxNMEA` derived class doesn't use any extra bytes of RAM. + +The `ubloxGPS` derived class adds 20 bytes to handle the more-complicated protocol, +plus 5 static bytes for converting GPS time and Time Of Week to UTC. + diff --git a/software/firmware/libraries/NeoGPS/extras/doc/Tradeoffs.md b/software/firmware/libraries/NeoGPS/extras/doc/Tradeoffs.md new file mode 100644 index 0000000..7bcab21 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/doc/Tradeoffs.md @@ -0,0 +1,40 @@ +Tradeoffs +========= + +There's a price for everything, hehe... + +#### Configurability means that the code is littered with #ifdef sections. + +I've tried to increase white space and organization to make it more readable, but let's be honest... +conditional compilation is ugly. + +#### Accumulating parts means knowing which parts are valid. + +Before accessing a part, you must check its `valid` flag. Fortunately, this adds only one bit per member. See [Streamers.cpp](/src/Streamers.cpp#L100) for an example of accessing every data member. That file also shows how to accommodate different builds: all references to 'gps_fix' members are wrapped with conditional compilation `#ifdef`/`#endif` statements. If you do not plan to support multiple configurations, you do not need to use `#ifdef`/`#endif` statements. + +#### Parsing without buffers, or *in place*, means that you must be more careful about when you access data items. + +In general, using the fix-oriented methods `available` and `read` are atomically safe. You can access any parts of your `fix` structure, at any time. + +If you are using the advanced [character-oriented methods](/extras/doc/CharOriented.md): + +* You must wait to access the internal `gps.fix()` until after the entire sentence has been parsed. +* Only 3 example programs use these methods: NMEAblink, NMEAorder and NMEAdiagnostic. These examples simply `decode` until a sentence is COMPLETED. See `GPSloop()` in [NMEAdiagnostic.ino](/examples/NMEAdiagnostoc/NMEAdiagnostic.ino). +* Member function `gps.is_safe()` can also be used to determine when it is safe to access the internal `gps.fix()`. +* Received data errors can cause invalid field values to be set in the internal fix *before* the CRC is fully computed. The CRC will +catch most of those, and the internal fix members will then be marked as invalid. + +#### Accumulating parts into *one* fix means less RAM but more complicated code + +By enabling one of the [merging](/extras/doc/Merging.md) methods, fixes will accumulate data from all received sentences. The code required to implement those different techniques is more complicated than simply setting a structure member. + +You are not restricted from having other instances of fix; you can copy or merge a some or all of a new fix into another copy if you want. + +#### Full C++ OO implementation is more advanced than most Arduino libraries. + +You've been warned! ;) + +#### "fast, good, cheap... pick two." + +Although most of the RAM reduction is due to eliminating buffers, some of it is from trading RAM +for additional code (see **Nominal** Program Space above). And, as I mentioned, the readabilty (i.e., goodness) suffers from its configurability. diff --git a/software/firmware/libraries/NeoGPS/extras/doc/Troubleshooting.md b/software/firmware/libraries/NeoGPS/extras/doc/Troubleshooting.md new file mode 100644 index 0000000..c63d1dd --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/doc/Troubleshooting.md @@ -0,0 +1,275 @@ +Troubleshooting +=============== +Most problems are caused by these kinds of errors: + 1. [Device connection](#gps-device-connection-problems) (use `NMEAdiagnostic.ino`) + 2. [Poor reception](#poor-reception) (use `NMEA.ino`) + 3. [Configuration](#configuration-errors) (use `NMEAtest.ino`) + 4. [Quiet Time Interval](#quiet-time-interval) (use `NMEAorder.ino`) + 5. [Trying to do too many things](#trying-to-do-too-many-things) at the same time + 6. [When all else fails...](#when-all-else-fails) + +__________________ +## GPS device connection problems +The example program `NMEAdiagnostic.ino` can several kinds of problems: + +1) The GPS device may not be correctly wired, +2) The GPS device is correctly wired but running at the wrong baud rate, +3) The GPS device is running at the correct baud rate, but it never sends the LAST_SENTENCE_IN_INTERVAL, as defined in NMEAGPS_cfg.h + +To help diagnose the problem, use [NMEAdiagnostic.ino](/examples/NMEAdiagnostic/NMEAdiagnostic.ino). Create an NMEAdiagnostic subdirectory, copy the same NeoGPS files into that subdirectory, along with NMEAdiagnostic.ino. Build and upload the sketch. + +##### 1) Not correctly wired +If the GPS device is not correctly connected, [NMEAdiagnostic.ino](/examples/NMEAdiagnostic/NMEAdiagnostic.ino) will display: +``` +NMEAdiagnostic.INO: started +Looking for GPS device on Serial1 + +____________________________ + +Checking 9600 baud... + + +Check GPS device and/or connections. No data received. +``` +The example program [NMEA.ino](/examples/NMEA/NMEA.ino) will display the following, stopping after printing the header: +``` +NMEA.INO: started + fix object size = 31 + gps object size = 84 +Looking for GPS device on Serial1 + +GPS quiet time is assumed to begin after a GST sentence is received. + You should confirm this with NMEAorder.ino + +Status,UTC Date/Time,Lat,Lon,Hdg,Spd,Alt,Sats,Rx ok,Rx err,Rx chars, +``` +You may have the GPS device connected to the wrong pins (GPS RX should be connected to Arduino TX, and GPS TX should be connected to Arduino RX), or the .INO may be using the wrong serial object: review `GPSport.h` for the expected connections, or delete the include and declare your own serial port variable. + +##### 2) Wrong baud rate +If the wrong baud rate is chosen, [NMEAdiagnostic.ino](/examples/NMEAdiagnostic/NMEAdiagnostic.ino) will try each baud rate to determine the correct baud rate for your GPS device. For each baud rate, it will display: +``` +Checking 4800 baud... +No valid sentences, but characters are being received. +Check baud rate or device protocol configuration. + +Received data: +884A0C4C8C480C8808884A0C8C480C4A4CC80A0C027759495995A5084C0A4C88 .J.L.H....J..H.JL....wYIY...L.L. +``` +If the example program [NMEA.ino](/examples/NMEA/NMEA.ino) is using the wrong baud rate, it will print lines of empty data: +``` +Local time,Status,UTC Date/Time,Lat,Lon,Hdg,Spd,Alt,HDOP,Rx ok,Rx err,Rx chars, +,,,,,,,,0,3,181, +,,,,,,,,0,1,422, +``` +Notice how the received character count (Rx chars) is increasing, but nothing was decoded successfully (Rx ok always 0), and a few sentences had errors. You should review your GPS device's documentation to find the correct baud rate, or use [NMEAdiagnostic](/examples/NMEAdiagnostic/NMEAdiagnostic.ino) to auto-detect the correct baud rate. +##### 3) Wrong LAST_SENTENCE_IN_INTERVAL in NMEAGPS_cfg.h +It is very important that the correct LAST_SENTENCE_IN_INTERVAL is chosen. It is used to determine what sentences are in a particular interval (usually 1 second) and when the GPS quiet time begins (see below). + +Choosing the wrong LAST_SENTENCE_IN_INTERVAL may cause GPS characters to be dropped (because the quiet time is assumed to begin at the wrong time), or prevent any update intervals from being completed (because the sketch waits for the wrong sentence to arrive). + +If the wrong LAST_SENTENCE_IN_INTERVAL is chosen, [NMEAdiagnostic.ino](/examples/NMEAdiagnostic/NMEAdiagnostic.ino) will display: +``` +NMEAdiagnostic.INO: started +Looking for GPS device on Serial1 + +____________________________ + +Checking 9600 baud... +Received GSV +Received GSV +Received GLL +Received RMC +Received VTG +Received GGA +Received GSA +Received GSV +Received GSV +Received GSV +Received GLL +Received RMC +Received VTG +Received GGA +Received GSA +Received GSV +Received GSV +Received GSV +Received GLL +Received RMC +Received VTG + + +**** NMEA sentence(s) detected! **** +Received data: +47504753562C332C312C31312C30322C37302C3330322C32372C30352C33352C GPGSV,3,1,11,02,70,302,27,05,35, +3139372C32342C30362C34392C3035332C33312C30392C31372C3037332C3230 197,24,06,49,053,31,09,17,073,20 +2A37360D0A2447504753562C332C322C31312C31322C35352C3236362C32352C *76..$GPGSV,3,2,11,12,55,266,25, + +Device baud rate is 9600 + +GPS data fields received: + + Status,UTC Date/Time,Lat,Lon,Hdg,Spd,Alt,Sats,Rx ok,Rx err,Rx chars, + 3,2016-05-24 01:56:45.00,456013948,-720168555,,816,25450,7,21,0,1317, + +Warning: LAST_SENTENCE_IN_INTERVAL defined to be RMC, but was never received. + Please use NMEAorder.ino to determine which sentences your GPS device sends, and then + use the last one for the definition in NMEAGPS_cfg.h. + +** NMEAdiagnostic completed ** + +1 warnings +``` +As instructed, you should run the NMEAorder.ino sketch to determine which sentence is last. You may be able to see a slight pause in the "Received XXX" messages above, which would also identify the last sentence. Edit NMEAGPS_cfg.ino and change this line: +``` +#define LAST_SENTENCE_IN_INTERVAL NMEAGPS::NMEA_GLL +``` +__________________ +## Poor reception +If the GPS device is correctly connected, and the sketch is receiving complete NMEA sentences, without data errors, [NMEA.ino](/examples/NMEA/NMEA.ino) displays "mostly" empty fields: +``` +Local time,Status,UTC Date/Time,Lat,Lon,Hdg,Spd,Alt,HDOP,Rx ok,Rx err,Rx chars, +,0,,,,,,,3,0,259, +,0,,,,,,,6,0,521, +``` +Notice how "Rx ok" and "Rx chars" increase each second, and "Rx err" is usually zero. This means that the sketch is receiving complete NMEA sentences, without data errors. + +Because the fields are all empty, the GPS device is not receiving signals from any satellites. Check the antenna connection and orientation, and make sure you have an unobstructed view of the sky: go outside for the best reception, although getting close to a window may help. + +Although different GPS devices behave differently when they do not have a fix, you may be able to determine how many satellites are being received from what is being reported. + +As soon as the GPS device receives a signal from just one satellite, the status may change to "1" and the date and time will be reported: +``` +Local time,Status,UTC Date/Time,Lat,Lon,Hdg,Spd,Alt,HDOP,Rx ok,Rx err,Rx chars, +2015-09-14 15:07:30,1,2015-09-14 19:07:30.00,,,,,,3,0,259, +2015-09-14 15:07:31,1,2015-09-14 19:07:30.00,,,,,,3,0,521, +``` +If it continues to report only date and time, you do not have an unobstructed view of the sky: only one satellite signal is being received. + +When signals from three satellites are being received, the GPS device will start reporting latitude and longitude. +When signals from four or more satellites are being received, the GPS device will start reporting altitude. + +You can also enable other `gps_fix` fields or NMEA sentences. In **GPSfix_cfg.h**, uncomment this line: +``` +#define GPS_FIX_SATELLITES +``` +In **NMEAGPS_cfg.h** uncomment these lines: +``` +#define NMEAGPS_PARSE_GGA +#define NMEAGPS_PARSE_GSA +#define NMEAGPS_PARSE_GSV + +#define NMEAGPS_PARSE_SATELLITES +#define NMEAGPS_PARSE_SATELLITE_INFO +#define NMEAGPS_MAX_SATELLITES (20) +``` +This will display additional fields for how many satellites are in view, whether they are being "tracked", and their individual signal strengths. +``` +Local time,Status,UTC Date/Time,Lat,Lon,Hdg,Spd,Alt,HDOP,VDOP,PDOP,Lat err,Lon err,Alt err,Sats,[sat elev/az @ SNR],Rx ok,Rx err,Rx chars, +2015-09-14 16:03:07,3,2015-09-14 20:03:07.00,,,,,,,,,,,,2,[2 71/27@14,5 65/197@33,],8,0,476, +2015-09-14 16:03:08,3,2015-09-14 20:03:08.00,,,,,,,,,,,,2,[2 71/27@14,5 65/197@33,],16,0,952, +``` +This shows that only two satellites are being tracked. You must move to a position with a better view of the sky. + +__________________ +## Quiet Time Interval +Because GPS devices send lots of data, it is possible for the Arduino input buffer to overflow. Many other libraries' examples will fail when modified to print too much information, or write to an SD card (see also [next section](#trying-to-do-too-many-things)). + +NeoGPS examples are structured in a way that takes advantage of a "quiet time" in the data stream. GPS devices send a batch of sentences, once per second. After the last sentence in the batch has been sent, the GPS device will not send any more data until the next interval. The example programs watch for that last sentence. When it is received, it is safe to perform time-consuming operations. + +It is **critical** to know the order of the sentences sent by your specific device. If you do not know what sentence is last in a batch, use the example program `NMEAorder.ino` to list the sentence order. When you know the last sentence, review `NMEAGPS_cfg.h` to confirm that the correct value on this line: + +``` +#define LAST_SENTENCE_IN_INTERVAL NMEAGPS::NMEA_GLL +``` + +Most example programs depend on this statement. `NMEAdiagnostic.ino` will emit a warning if that sentence is never recevied. If `LAST_SENTENCE_IN_INTERVAL` is not correct for your device, the example programs will probably lose GPS data, especially on `SoftwareSerial` data ports. The example programs may behave like they are using the wrong baud rate: empty fields, increasing Rx Errors, and increasing Rx Chars. Basically, the example programs are [Trying To Do Too Much](#trying-to-do-too-many-things) at the wrong time. With the correct `LAST_SENTENCE_IN_INTERVAL`, the example programs will not lose GPS data. + +## Configuration errors +Because there are so many configurable items, it is possible that your configuration prevents acquiring the desired GPS information. + +The compiler **cannot** catch message set dependencies: the enum +`nmea_msg_t` is always available. So even though a `fix` member is enabled, +you may have disabled all messages that would have set its value. +`NMEAtest.ino` can be used to check some configurations. + +For example, if your application needs altitude, you **must** enable the GGA sentence. No other sentence provides the altitude member (see [this table](Choosing.md)). If `NMEA_PARSE_GGA` is not defined, `gps.decode()` will return COMPLETED after a GGA is received, but no parts of the GGA sentence will have been parsed, and altitude will never be valid. NeoGPS will _recognize_ the GGA sentence, but it will not be parsed. + +The compiler will catch any attempt to use parts of a `fix` that have been +configured out: you will see something like `gps_fix does not have member +xxx`. + +There are also compile-time checks to make sure the configuration is valid. For example, if you enable `NMEAGPS_PARSE_SATELLITES` so that you can access the array of satellite information, you *must* enable `GPS_FIX_SATELLITES`. An error message will tell you to do that. Until you disable `NMEAGPS_PARSE_SATELLITES` **or** enable `GPS_FIX_SATELLITES`, it will not compile. + +__________________ +## Trying to do too many things +Many libraries and their examples, and I mean almost all of 'em, are not structured in a way that lets you do more than one thing in a sketch. The result: the example program works great, but adding anything to it breaks it. + +#### Printing too much +Many programmers run into trouble because they try to print too much debug info. The Arduino `Serial.print` function will "block" until those output characters can be stored in a buffer. While the sketch is blocked at `Serial.print`, the GPS device is probably still sending data. The _input_ buffer on an Arduino is only 64 bytes, about the size of one NMEA sentence. After 64 bytes have been received stored, all other data is dropped! Depending on the GPS baud rate and the Serial Monitor baud rate, it may be very easy to lose GPS characters. + +It is crucial to call `gps.available( gps_port )` or `serial.read()` frequently, and _never_ to call a blocking function that takes more than (64*11/baud) seconds. If the GPS is running at 9600, you cannot block for more than 70ms. If your debug `Serial` is also running at 9600, you cannot write more than 64 bytes consecutively (i.e., in less than 70ms). + +#### Blocking operations +Most Arduino libraries are written in a blocking fashion. That is, if you call a library's function, it will not return from that function until the operation has been completed. If that operation takes a long time, GPS characters will be dropped. + +Many programmers want to write GPS data to an SD card. This is completely reasonable to do, but an `SD.write` can block long enough to cause the input buffer to overflow. SD libraries have their own buffers, and when they are filled, the library performs SPI operations to "flush" the buffer to the SD card. While that is happening, the GPS device is _still_ sending data, and it will eventually overflow the serial input buffer. + +This is a very common problem! Here are some diagrams to help explain the timing for the Adafruit_GPS library. First, lets look at how the incoming GPS data relates to reading and parsing it: + + + +Note how loop calls GPS.read, and when it has read all the chars that have been received up to that point, it returns. loop may get called lots of times while it's waiting for the chars to come in. Eventually, the whole sentence is received, newNMEAreceived returns true, and your sketch can `parse` the new data (not needed for **NeoGPS**). + +The problem is that if you try to do anything that takes "too long", `GPS.read` won't get called. The incoming chars stack up in the input buffer until it's full. After that, the chars will be dropped: + + + +The next sentence, a GPRMC, continues to come in while `Serial.print` and `SD.write` are doing their thing... and data gets lost. + +Fortunately, there are two ways to work around this: + +#### **1)** Use an interrupt-driven approach + +The received data could be handled by an **I**nterrupt **S**ervice **R**outine. The example program [NMEA_isr.INO](/examples/NMEA_isr/NMEA_isr.ino) shows how to handle the received GPS characters *during* the RX interrupt. This program uses one of the replacement **NeoXXSerial** libraries to attach an interrupt handler to the GPS serial port. + +When a character is received, the ISR is called, where it is immediately decoded. Normally, the character is stored in an input buffer, and you have to call `available()` and then `read()` to retrieve the character. Handling it in the ISR totally avoids having to continuously call `Serial1.read()`, and is much more efficient. Your program does not have to be structured around the GPS quiet time. + +The ISR can also save (i.e., "buffer") complete fixes as they are completed. This allows the main sketch to perform an operation that takes multiple update intervals. This is especially important if your GPS is sending updates 10 times per second (10Hz), and your SD card takes ~150ms to complete a logging write. + +Normally, this would cause a loss of data. You can specify the number of fixes to be stored by the ISR for later use: simply set NMEAGPS_FIX_MAX to 2. This will allow 2 complete fixes, accumulated from several sentences each, to be stored until `loop()` can call `gps.read()`. This is referred to as "fix-oriented operation" in the Data Model description. + +While interrupt handling is considered a more advanced technique, it is similar to the existing Arduino [attachInterrupt](https://www.arduino.cc/en/Reference/AttachInterrupt) function for detecting when pin change. + +Which **NeoXXLibrary** should you use? + +* If `Serial` or `Serial1` is connected to the GPS device, you can use [NeoHWSerial](https://github.com/SlashDevin/NeoHWSerial). +* If the Input Capture pin can be connected to the GPS device, as required for AltSoftSerial, you can use [NeoICSerial](https://github.com/SlashDevin/NeoICSerial). +* If neither of those connections is possible, you can [NeoSWSerial](https://github.com/SlashDevin/NeoSWSerial) on almost any pair of digital pins. It only supports a few baud rates, though. + +#### **2)** Restructure `loop()` to do time-consuming operations during the GPS [quiet time](#quiet-time-interval). + +All non-ISR example programs are structured this way. The "quiet time" is perfect for doing other things: + + + +All you need to do is hold on to the GPS information (date, time, location, etc.) until the quiet time comes around. You'll need to take the same approach for each additional task. For additional sensors, hold on to the temperature, acceleration, whatever, until the quiet time comes around. *Then* perform the blocking operation, like `SD.write`, and no GPS data will be lost. + +This is why NeoGPS uses a `fix` structure: it can be + * _populated_ as the characters are received, + * _copied/merged_ when a sentence is complete, and then + * _used_ anytime (for fast operations) or during the quiet time (for slow operations). + +You do not have to call a "parse" function after a complete sentence has been received -- the data was parsed as it was received. Essentially, the processing time for parsing is spread out across the receipt of all characters. When the last character of the sentence is received (i.e. `gps.available()` or `gps.decode(c) == DECODE_COMPLETED`), the relevant members of `gps.fix()` have already been populated. + +These example programs are structured so that the (relatively) slow printing operations are performed during the GPS quiet time. Simply replace those trace/print statements with your specific code. + +__________________ +## When all else fails + +If you still do not have enough time to complete your tasks during the GPS quiet time, you can + * Increase the baud rate on the debug port (takes less time to print) + * Increase the baud rate on the GPS port (increases quiet time) + * Configure the GPS device to send fewer sentences (decreases parsing time, increases quiet time) + * Use a binary protocol for your specific device (decreases parsing time, increases quiet time) + * Watch for a specific message to be COMPLETED, then begin your specific processing. This may cause some sentences to lose characters, but they may not be necessary. See comments regarding `LAST_SENTENCE_IN_INTERVAL` above. + * Use the interrupt-driven approach, described above. It is *guaranteed* to work! diff --git a/software/firmware/libraries/NeoGPS/extras/doc/readme.txt b/software/firmware/libraries/NeoGPS/extras/doc/readme.txt new file mode 100644 index 0000000..3f6bcea --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/doc/readme.txt @@ -0,0 +1 @@ +These .MD files are in github markdown format. They are intended to be read on the github website, as linked from the top repository page. diff --git a/software/firmware/libraries/NeoGPS/extras/doc/ublox.md b/software/firmware/libraries/NeoGPS/extras/doc/ublox.md new file mode 100644 index 0000000..325c607 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/extras/doc/ublox.md @@ -0,0 +1,61 @@ +NeoGPS support for u-blox GPS devices +================= +To use either ublox-specific NMEA messages ($PUBX) or the UBX binary protocol, you must enable the following in `NMEAGPS_cfg.h`: +``` +#define NMEAGPS_PARSE_MFR_ID + +#define NMEAGPS_DERIVED_TYPES +``` + +## ublox-specific NMEA messages +**NeoGPS** implements the following additional NMEA messages: + +#NMEA 0183 Proprietary Messages +* UBX,00 - Lat/Long Position Data +* UBX,04 - Time of Day and Clock Information + +You may want to change the configured PUBX messages in `ubxNMEA.h`. It is currently configured to work with the example application, `PUBX.ino`. + +The derived class `ubloxNMEA` has the following configuration items near the top of ubxNMEA.h: +``` +#define NMEAGPS_PARSE_PUBX_00 +#define NMEAGPS_PARSE_PUBX_04 +``` + +## ublox-specific binary protocol + +**NeoGPS** implements the following messages in the UBX binary protocol: + +#UBX Protocol Messages + +* NAV_STATUS - Receiver Navigation Status +* NAV_TIMEGPS - GPS Time Solution +* NAV_TIMEUTC - UTC Time Solution +* NAV_POSLLH - Geodetic Position Solution +* NAV_VELNED - Velocity Solution in NED (North/East/Down) +* NAV_SVINFO - Space Vehicle Information + +You may want to change the configured UBX messages in `ubx_cfg.h`. It is currently configured to work with the example application `ublox.ino`. + +The configuration file `ubx_cfg.h` has the following configuration items near the top of the file: +``` +#define UBLOX_PARSE_STATUS +#define UBLOX_PARSE_TIMEGPS +#define UBLOX_PARSE_TIMEUTC +#define UBLOX_PARSE_POSLLH +//#define UBLOX_PARSE_DOP +#define UBLOX_PARSE_VELNED +#define UBLOX_PARSE_SVINFO +``` + +**Note:** Disabling some of the UBX messages may prevent the `ublox.ino` example sketch from working. That sketch goes through a process of first acquiring the current GPS leap seconds and UTC time so that "time-of-week" milliseconds can be converted to a UTC time. + +The POSLLH and VELNED messages use a Time-Of-Week timestamp. Without the TIMEGPS and TIMEUTC messages, that TOW timestamp cannot be converted to a UTC time. + +* If your application does not need the UTC date and/or time, you could disable the TIMEGPS and TIMEUTC messages. + +* If your application does not need latitude, longitude or altitude, you could disable the POSLLH message. + +* If your application does not need speed or heading, you could disable the VELNED message. + +* If your application does not need satellite information, you could disable the SVINFO message. diff --git a/software/firmware/libraries/NeoGPS/library.properties b/software/firmware/libraries/NeoGPS/library.properties new file mode 100644 index 0000000..b792ae2 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/library.properties @@ -0,0 +1,10 @@ +name=NeoGPS +version=4.2.3 +author=SlashDevin +maintainer=SlashDevin +sentence=NMEA and ublox GPS parser, configurable to use as few as 10 bytes of RAM +paragraph=Faster and smaller than all other GPS parsers +category=Communication +url=https://github.com/SlashDevin/NeoGPS +architectures=avr,samd,sam,esp8266,arc32,esp32 +includes=NMEAGPS.h diff --git a/software/firmware/libraries/NeoGPS/src/CosaCompat.h b/software/firmware/libraries/NeoGPS/src/CosaCompat.h new file mode 100644 index 0000000..ad9c080 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/src/CosaCompat.h @@ -0,0 +1,34 @@ +#ifndef COSACOMPAT_H +#define COSACOMPAT_H + +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . + +#ifdef __AVR__ + + #include + +#else + + #define PGM_P const char * + +#endif + +typedef PGM_P str_P; +#define __PROGMEM PROGMEM + +#endif \ No newline at end of file diff --git a/software/firmware/libraries/NeoGPS/src/DMS.cpp b/software/firmware/libraries/NeoGPS/src/DMS.cpp new file mode 100644 index 0000000..198eb0a --- /dev/null +++ b/software/firmware/libraries/NeoGPS/src/DMS.cpp @@ -0,0 +1,121 @@ +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . + +#include "DMS.h" + +#include + +//---------------------------------------------------------------- +// Note that no division is used, and shifts are on byte boundaries. Fast! + +void DMS_t::From( int32_t deg_1E7 ) +{ + const uint32_t E7 = 10000000UL; + + if (deg_1E7 < 0) { + deg_1E7 = -deg_1E7; + hemisphere = SOUTH_H; // or WEST_H + } else + hemisphere = NORTH_H; // or EAST_H + + const uint32_t div_E32 = 429; // 1e-07 * 2^32 + degrees = ((deg_1E7 >> 16) * div_E32) >> 16; + uint32_t remainder = deg_1E7 - degrees * E7; + + remainder *= 60; // to minutes * E7 + minutes = ((remainder >> 16) * div_E32) >> 16; + remainder -= minutes * E7; + + remainder *= 60; // to seconds * E7 + uint32_t secs = ((remainder >> 16) * div_E32) >> 16; + remainder -= secs * E7; + + const uint32_t div_1E4_E24 = 1677; // 0.00001 * 2^24 + seconds_frac = (((remainder >> 8) * div_1E4_E24) >> 16); // thousandths + seconds_whole = secs; + + // Carry if thousandths too big + if (seconds_frac >= 1000) { + seconds_frac -= 1000; + seconds_whole++; + if (seconds_whole >= 60) { + seconds_whole -= 60; + minutes++; + if (minutes >= 60) { + minutes -= 60; + degrees++; + } + } + } + +} // From + +//---------------------------------------------------------------- + +Print & operator << ( Print & outs, const DMS_t & dms ) +{ + if (dms.degrees < 10) + outs.write( '0' ); + outs.print( dms.degrees ); + outs.write( ' ' ); + if (dms.minutes < 10) + outs.write( '0' ); + outs.print( dms.minutes ); + outs.print( F("\' ") ); + if (dms.seconds_whole < 10) + outs.write( '0' ); + outs.print( dms.seconds_whole ); + outs.write( '.' ); + if (dms.seconds_frac < 100) + outs.write( '0' ); + if (dms.seconds_frac < 10) + outs.write( '0' ); + outs.print( dms.seconds_frac ); + outs.print( F("\" ") ); + + return outs; + +} // operator << + +//---------------------------------------------------------------- + +void DMS_t::printDDDMMmmmm( Print & outs ) const +{ + outs.print( degrees ); + + if (minutes < 10) + outs.print( '0' ); + outs.print( minutes ); + outs.print( '.' ); + + // Calculate the fractional minutes from the seconds, + // *without* using floating-point numbers. + + uint16_t mmmm = seconds_whole * 166; // same as 10000/60, less .66666... + mmmm += (seconds_whole * 2 + seconds_frac/2 ) / 3; // ... plus the remaining .66666 + // ... plus the seconds_frac, scaled by 10000/(60*1000) = 1/6, which + // is implemented above as 1/2 * 1/3 + + // print leading zeroes, if necessary + if (mmmm < 1000) + outs.print( '0' ); + if (mmmm < 100) + outs.print( '0' ); + if (mmmm < 10) + outs.print( '0' ); + outs.print( mmmm ); +} \ No newline at end of file diff --git a/software/firmware/libraries/NeoGPS/src/DMS.h b/software/firmware/libraries/NeoGPS/src/DMS.h new file mode 100644 index 0000000..bcd9986 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/src/DMS.h @@ -0,0 +1,55 @@ +#ifndef DMS_H +#define DMS_H + +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . + +#include "NeoGPS_cfg.h" +#include +class Print; + +enum Hemisphere_t { NORTH_H = 0, SOUTH_H = 1, EAST_H = 0, WEST_H = 1 }; + +class DMS_t +{ +public: + uint8_t degrees; + uint8_t minutes ;//NEOGPS_BF(6); + Hemisphere_t hemisphere ;//NEOGPS_BF(2); compiler bug! + uint8_t seconds_whole NEOGPS_BF(6); + uint16_t seconds_frac NEOGPS_BF(10); // 1000ths + + void init() { degrees = minutes = seconds_whole = seconds_frac = 0; + hemisphere = NORTH_H; } + + float secondsF() const { return seconds_whole + 0.001 * seconds_frac; }; + char NS () const { return (hemisphere == SOUTH_H) ? 'S' : 'N'; }; + char EW () const { return (hemisphere == WEST_H) ? 'W' : 'E'; }; + + //............................................................................. + // A utility function to convert from integer 'lat' or 'lon', scaled by 10^7 + + void From( int32_t deg_1E7 ); + + // Print DMS as the funky NMEA DDDMM.mmmm format + void printDDDMMmmmm( Print & outs ) const; + +} NEOGPS_PACKED; + +extern Print & operator << ( Print & outs, const DMS_t & ); + +#endif \ No newline at end of file diff --git a/software/firmware/libraries/NeoGPS/src/GPSTime.cpp b/software/firmware/libraries/NeoGPS/src/GPSTime.cpp new file mode 100644 index 0000000..cee247f --- /dev/null +++ b/software/firmware/libraries/NeoGPS/src/GPSTime.cpp @@ -0,0 +1,21 @@ +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . + +#include "GPSTime.h" + +uint8_t GPSTime::leap_seconds = 0; +NeoGPS::clock_t GPSTime::s_start_of_week = 0; diff --git a/software/firmware/libraries/NeoGPS/src/GPSTime.h b/software/firmware/libraries/NeoGPS/src/GPSTime.h new file mode 100644 index 0000000..235dc07 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/src/GPSTime.h @@ -0,0 +1,85 @@ +#ifndef GPSTIME_H +#define GPSTIME_H + +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . + +#include "NeoTime.h" + +class GPSTime +{ + GPSTime(); + + static NeoGPS::clock_t s_start_of_week; + +public: + + /** + * GPS time is offset from UTC by a number of leap seconds. To convert a GPS + * time to UTC time, the current number of leap seconds must be known. + * See http://en.wikipedia.org/wiki/Global_Positioning_System#Leap_seconds + */ + static uint8_t leap_seconds; + + /** + * Some receivers report time WRT start of the current week, defined as + * Sunday 00:00:00. To save fairly expensive date/time calculations, + * the UTC start of week is cached + */ + static void start_of_week( NeoGPS::time_t & now ) + { + now.set_day(); + s_start_of_week = + (NeoGPS::clock_t) now - + (NeoGPS::clock_t) ((((now.day-1 ) * 24L + + now.hours ) * 60L + + now.minutes) * 60L + + now.seconds); + } + + static NeoGPS::clock_t start_of_week() + { + return s_start_of_week; + } + + /* + * Convert a GPS time-of-week to UTC. + * Requires /leap_seconds/ and /start_of_week/. + */ + static NeoGPS::clock_t TOW_to_UTC( uint32_t time_of_week ) + { return (NeoGPS::clock_t) + (start_of_week() + time_of_week - leap_seconds); } + + /** + * Set /fix/ timestamp from a GPS time-of-week in milliseconds. + * Requires /leap_seconds/ and /start_of_week/. + **/ + static bool from_TOWms + ( uint32_t time_of_week_ms, NeoGPS::time_t &dt, uint16_t &ms ) + { +//trace << PSTR("from_TOWms(") << time_of_week_ms << PSTR("), sow = ") << start_of_week() << PSTR(", leap = ") << leap_seconds << endl; + bool ok = (start_of_week() != 0) && (leap_seconds != 0); + if (ok) { + NeoGPS::clock_t tow_s = time_of_week_ms/1000UL; + dt = TOW_to_UTC( tow_s ); + ms = (uint16_t)(time_of_week_ms - tow_s*1000UL); + } + return ok; + } +}; + +#endif \ No newline at end of file diff --git a/software/firmware/libraries/NeoGPS/src/GPSfix.h b/software/firmware/libraries/NeoGPS/src/GPSfix.h new file mode 100644 index 0000000..93d834f --- /dev/null +++ b/software/firmware/libraries/NeoGPS/src/GPSfix.h @@ -0,0 +1,501 @@ +#ifndef GPSFIX_H +#define GPSFIX_H + +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . + +#include "NeoGPS_cfg.h" +#include "GPSfix_cfg.h" + +#if defined( GPS_FIX_DATE ) | defined( GPS_FIX_TIME ) + #include "NeoTime.h" +#endif + +#ifdef GPS_FIX_LOCATION_DMS + #include "DMS.h" +#endif + +#ifdef GPS_FIX_LOCATION + #include "Location.h" +#endif + +/** + * A structure for holding a GPS fix: time, position, velocity, etc. + * + * Because GPS devices report various subsets of a coherent fix, + * this class tracks which members of the fix are being reported: + * each part has its own validity flag. Also, operator |= implements + * merging multiple reports into one consolidated report. + * + * @section Limitations + * Reports are not really fused with an algorithm; if present in + * the source, they are simply replaced in the destination. + * + */ + +class gps_fix +{ +public: + + // Default Constructor + gps_fix() { init(); }; + + //------------------------------------------------------------------ + // 'whole_frac' is a utility structure that holds the two parts + // of a floating-point number. + // + // This is used for Altitude, Heading and Speed, which require more + // significant digits than a 16-bit number. + // + // When parsing floating-point fields, the decimal point is used as + // a separator for these two parts. This is much more efficient + // than calling 'long' or 'floating-point' math subroutines. + // + // This requires knowing the exponent on the fraction when a simple type + // (e.g., float or int) is needed. For example, 'altitude()' knows that + // the whole part was stored as integer meters, and the fractional part + // was stored as integer centimeters. + // + // Unless you want the speed and precision of the two integer parts, you + // shouldn't have to use 'whole_frac'. Instead, use the + // accessor functions for each of the specific fields for + // Altitude, Heading and Speed. + + struct whole_frac { + int16_t whole; + int16_t frac; + void init() { whole = 0; frac = 0; }; + int32_t int32_00() const { return ((int32_t)whole) * 100L + frac; }; + int16_t int16_00() const { return whole * 100 + frac; }; + int32_t int32_000() const { return whole * 1000L + frac; }; + float float_00() const { return ((float)whole) + ((float)frac)*0.01; }; + float float_000() const { return ((float)whole) + ((float)frac)*0.001; }; + } NEOGPS_PACKED; + + //-------------------------------------------------------------- + // Members of a GPS fix + // + // Each member is separately enabled or disabled by the CFG file + // by #ifdef/#endif wrappers. + // Each member has a storage declaration that depends on the + // precision and type of data available from GPS devices. + // Some members have a separate accessor function that converts the + // internal storage type to a more common or convenient type + // for use by an application. + // For example, latitude data is internally stored as a 32-bit integer, + // where the reported degrees have been multiplied by 10^7. Many + // applications expect a floating-point value, so a floating-point + // accessor is provided: 'latitude()'. This function converts the + // internal 32-bit integer to a floating-point value, and then + // divides it by 10^7. The returned value is now a floating-point + // degrees value. + + #ifdef GPS_FIX_LOCATION + NeoGPS::Location_t location; + + int32_t latitudeL() const { return location.lat (); }; + float latitude () const { return location.latF(); }; // accuracy loss + + int32_t longitudeL() const { return location.lon (); }; + float longitude () const { return location.lonF(); }; // accuracy loss + #endif + + #ifdef GPS_FIX_LOCATION_DMS + DMS_t latitudeDMS; + DMS_t longitudeDMS; + #endif + + #ifdef GPS_FIX_ALTITUDE + whole_frac alt; // .01 meters + + int32_t altitude_cm() const { return alt.int32_00(); }; + float altitude () const { return alt.float_00(); }; + float altitude_ft() const { return altitude() * 3.28084; }; + #endif + + #ifdef GPS_FIX_SPEED + whole_frac spd; // .001 nautical miles per hour + + uint32_t speed_mkn () const { return spd.int32_000(); }; + float speed () const { return spd.float_000(); }; + + // Utilities for speed in other units + CONST_CLASS_DATA float KM_PER_NMI = 1.852; + float speed_kph () const { return speed() * KM_PER_NMI; }; + + CONST_CLASS_DATA uint16_t M_PER_NMI = 1852; + uint32_t speed_metersph() const { return (spd.whole * M_PER_NMI) + (spd.frac * M_PER_NMI)/1000; }; + + CONST_CLASS_DATA float MI_PER_NMI = 1.150779; + float speed_mph() const { return speed() * MI_PER_NMI; }; + #endif + + #ifdef GPS_FIX_HEADING + whole_frac hdg; // .01 degrees + + uint16_t heading_cd() const { return hdg.int16_00(); }; + float heading () const { return hdg.float_00(); }; + #endif + + //-------------------------------------------------------- + // Dilution of Precision is a measure of the current satellite + // constellation geometry WRT how 'good' it is for determining a + // position. This is _independent_ of signal strength and many + // other factors that may be internal to the receiver. + // It _cannot_ be used to determine position accuracy in meters. + // Instead, use the LAT/LON/ALT error in cm members, which are + // populated by GST sentences. + + #ifdef GPS_FIX_HDOP + uint16_t hdop; // Horizontal Dilution of Precision x 1000 + #endif + #ifdef GPS_FIX_VDOP + uint16_t vdop; // Vertical Dilution of Precision x 1000 + #endif + #ifdef GPS_FIX_PDOP + uint16_t pdop; // Position Dilution of Precision x 1000 + #endif + + //-------------------------------------------------------- + // Error estimates for latitude, longitude and altitude, in centimeters. + + #ifdef GPS_FIX_LAT_ERR + uint16_t lat_err_cm; + float lat_err() const { return lat_err_cm / 100.0; } + #endif + + #ifdef GPS_FIX_LON_ERR + uint16_t lon_err_cm; + float lon_err() const { return lon_err_cm / 100.0; } + #endif + + #ifdef GPS_FIX_ALT_ERR + uint16_t alt_err_cm; + float alt_err() const { return alt_err_cm / 100.0; } + #endif + + //-------------------------------------------------------- + // Height of the geoid above the WGS84 ellipsoid + #ifdef GPS_FIX_GEOID_HEIGHT + whole_frac geoidHt; // .01 meters + + int32_t geoidHeight_cm() const { return geoidHt.int32_00(); }; + float geoidHeight () const { return geoidHt.float_00(); }; + #endif + + //-------------------------------------------------------- + // Number of satellites used to calculate a fix. + #ifdef GPS_FIX_SATELLITES + uint8_t satellites; + #endif + + //-------------------------------------------------------- + // Date and Time for the fix + #if defined(GPS_FIX_DATE) | defined(GPS_FIX_TIME) + NeoGPS::time_t dateTime ; // Date and Time in one structure + #endif + #if defined(GPS_FIX_TIME) + uint8_t dateTime_cs; // The fix's UTC hundredths of a second + uint32_t dateTime_us() const // The fix's UTC microseconds + { return dateTime_cs * 10000UL; }; + uint16_t dateTime_ms() const // The fix's UTC millseconds + { return dateTime_cs * 10; }; + #endif + + //-------------------------------------------------------- + // The current fix status or mode of the GPS device. + // + // Unfortunately, the NMEA sentences are a little inconsistent + // in their use of "status" and "mode". Both fields are mapped + // onto this enumerated type. Be aware that different + // manufacturers interpret them differently. This can cause + // problems in sentences which include both types (e.g., GPGLL). + // + // Note: Sorted by increasing accuracy. See also /operator |=/. + + enum status_t { + STATUS_NONE, + STATUS_EST, + STATUS_TIME_ONLY, + STATUS_STD, + STATUS_DGPS, + STATUS_RTK_FLOAT, + STATUS_RTK_FIXED, + STATUS_PPS // Precise Position System, *NOT* Pulse-per-second + }; + + status_t status NEOGPS_BF(8); + + //-------------------------------------------------------- + // Flags to indicate which members of this fix are valid. + // + // Because different sentences contain different pieces of a fix, + // each piece can be valid or NOT valid. If the GPS device does not + // have good reception, some fields may not contain any value. + // Those empty fields will be marked as NOT valid. + + struct valid_t { + bool status NEOGPS_BF(1); + + #if defined(GPS_FIX_DATE) + bool date NEOGPS_BF(1); + #endif + + #if defined(GPS_FIX_TIME) + bool time NEOGPS_BF(1); + #endif + + #if defined( GPS_FIX_LOCATION ) | defined( GPS_FIX_LOCATION_DMS ) + bool location NEOGPS_BF(1); + #endif + + #ifdef GPS_FIX_ALTITUDE + bool altitude NEOGPS_BF(1); + #endif + + #ifdef GPS_FIX_SPEED + bool speed NEOGPS_BF(1); + #endif + + #ifdef GPS_FIX_HEADING + bool heading NEOGPS_BF(1); + #endif + + #ifdef GPS_FIX_SATELLITES + bool satellites NEOGPS_BF(1); + #endif + + #ifdef GPS_FIX_HDOP + bool hdop NEOGPS_BF(1); + #endif + #ifdef GPS_FIX_VDOP + bool vdop NEOGPS_BF(1); + #endif + #ifdef GPS_FIX_PDOP + bool pdop NEOGPS_BF(1); + #endif + + #ifdef GPS_FIX_LAT_ERR + bool lat_err NEOGPS_BF(1); + #endif + + #ifdef GPS_FIX_LON_ERR + bool lon_err NEOGPS_BF(1); + #endif + + #ifdef GPS_FIX_ALT_ERR + bool alt_err NEOGPS_BF(1); + #endif + + #ifdef GPS_FIX_GEOID_HEIGHT + bool geoidHeight NEOGPS_BF(1); + #endif + + // Initialize all flags to false + void init() + { + uint8_t *all = (uint8_t *) this; + for (uint8_t i=0; i. + +/** + * Enable/disable the storage for the members of a fix. + * + * Disabling a member prevents it from being parsed from a received message. + * The disabled member cannot be accessed or stored, and its validity flag + * would not be available. It will not be declared, and code that uses that + * member will not compile. + * + * DATE and TIME are somewhat coupled in that they share a single `time_t`, + * but they have separate validity flags. + * + * See also note regarding the DOP members, below. + * + */ + +#define GPS_FIX_DATE +#define GPS_FIX_TIME +#define GPS_FIX_LOCATION +//#define GPS_FIX_LOCATION_DMS +#define GPS_FIX_ALTITUDE +#define GPS_FIX_SPEED +#define GPS_FIX_HEADING +#define GPS_FIX_SATELLITES +//#define GPS_FIX_HDOP +//#define GPS_FIX_VDOP +//#define GPS_FIX_PDOP +//#define GPS_FIX_LAT_ERR +//#define GPS_FIX_LON_ERR +//#define GPS_FIX_ALT_ERR +//#define GPS_FIX_GEOID_HEIGHT + +#endif diff --git a/software/firmware/libraries/NeoGPS/src/GPSport.h b/software/firmware/libraries/NeoGPS/src/GPSport.h new file mode 100644 index 0000000..e0e3ece --- /dev/null +++ b/software/firmware/libraries/NeoGPS/src/GPSport.h @@ -0,0 +1,271 @@ +#ifndef GPSport_h +#define GPSport_h + +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . + +//----------------------------------------------------------- +// There are 2 ways this file can be used: +// +// I. AS IS, which tries to *guess* which port a beginner should use. +// If you include , , , +// *OR* before this file (in the INO) +// or on line 152 below, one of those ports will be used for the GPS. +// This file cannot always guess what you want, so you may need to use it +// in the 2nd way... +// +// II. *REPLACE EVERYTHING* in this file to *specify* which port and +// which library you want to use for that port. Just declare the +// port here. You must declare three things: +// +// 1) the "gpsPort" variable (used by all example programs), +// 2) the string for the GPS_PORT_NAME (displayed by all example programs), and +// 3) the DEBUG_PORT to use for Serial Monitor print messages (usually Serial). +// +// The examples will display the device you have selected during setup(): +// +// DEBUG_PORT.println( F("Looking for GPS device on " GPS_PORT_NAME) ); +// +// Choosing the serial port connection for your GPS device is probably +// the most important design decision, because it has a tremendous impact +// on the processor load. Here are the possible configurations, +// from BEST to WORST: +// +// --- The BEST choice is to use a HardwareSerial port. You could use Serial +// on any board, but you will have to disconnect the Arduino RX pin 0 +// from the GPS TX pin to upload a new sketch over USB. This is a very +// reliable connection: +// +// #define gpsPort Serial +// #define GPS_PORT_NAME "Serial" +// #define DEBUG_PORT Serial +// +// If you have a Mega, Leo or Due board, you could use Serial1, +// Serial2 or Serial3: +// +// #define gpsPort Serial1 +// #define GPS_PORT_NAME "Serial1" +// #define DEBUG_PORT Serial +// +// These extra ports do not have to be disconnected to upload new +// sketches over USB. +// +// Use NeoHWSerial if you want to handle GPS characters +// in an Interrupt Service Routine (see NMEA_isr.INO). +// Also uncomment NMEAGPS_INTERRUPT_PROCESSING in NMEAGPS_cfg.h. +// +// #include +// #define gpsPort NeoSerial +// #define GPS_PORT_NAME "NeoSerial" +// #define DEBUG_PORT NeoSerial +// +// Note that the DEBUG_PORT must be NeoSerial, not Serial +// (see NeoHWSerial documentation for additional requirements). +// +// --- The SECOND BEST choice is AltSoftSerial. It uses 10x to 500x +// more processor time than a HardwareSerial port, but it is the BEST +// *software* serial port library. It only works on two specific pins +// (see the AltSoftSerial documentation). +// +// #include +// AltSoftSerial gpsPort; // 8 & 9 for an UNO +// #define GPS_PORT_NAME "AltSoftSerial" +// #define DEBUG_PORT Serial +// +// Use NeoICSerial if you want to handle GPS characters +// in an Interrupt Service Routine (see NMEA_isr.INO). +// Also uncomment NMEAGPS_INTERRUPT_PROCESSING in NMEAGPS_cfg.h. +// +// #include +// NeoICSerial gpsPort; // 8 & 9 for an UNO +// #define GPS_PORT_NAME "NeoICSerial" +// #define DEBUG_PORT Serial +// +// --- The THIRD BEST choice is NeoSWSerial. It is almost as efficient as +// AltSoftSerial, but it only supports baud rates 9600, 19200 or 38400. +// +// #include +// NeoSWSerial gpsPort(3, 2); +// #define GPS_PORT_NAME "NeoSWSerial(3,2)" +// #define DEBUG_PORT Serial +// +// NeoSWSerial supports handling GPS characters in an Interrupt Service +// Routine (see NMEA_isr.INO). If you want to do that, also uncomment +// NMEAGPS_INTERRUPT_PROCESSING in NMEAGPS_cfg.h. +// +// --- The WORST choice is SoftwareSerial. IT IS NOT RECOMMENDED because +// it disables interrupts for the entire time a character is sent OR +// received. This interferes with other parts of your sketch or with +// other libraries. It prevents receiving or sending data on any other +// port. It cannot transmit and receive at the same time. 95% of the +// CPU time will be spent twiddling its thumbs. It may support 57600, +// but 115200 is rarely reliable. +// +// #include +// SoftwareSerial gpsPort(2,3); +// #define GPS_PORT_NAME "SoftwareSerial(8,9)" +// #define DEBUG_PORT Serial +// +// You should *seriously* consider using other pins or lower baud rates, +// so that you could use one of the other recommended ports. +//----------------------------------------------------------- + +// DEFAULT file contents: +// *GUESS* which port should be used. If you know what port you want to use, +// *DELETE* the rest of this file and declare your own GPS port variable, +// GPS port name string, and debug print port variable (see above). + +#if defined(SERIAL_PORT_HARDWARE_OPEN) + + #if SERIAL_PORT_HARDWARE_OPEN == Serial1 + + // This Arduino has more than one hardware serial port, + // use Serial1 (or NeoSerial1). + #define NEOGPS_USE_SERIAL1 + + #endif + +#endif + +#ifdef NEOGPS_USE_SERIAL1 + + #if defined( NMEAGPS_INTERRUPT_PROCESSING ) + #include + #define gpsPort NeoSerial1 + #define GPS_PORT_NAME "NeoSerial1" + #else + #define gpsPort Serial1 + #define GPS_PORT_NAME "Serial1" + #endif + +#else + // Uncomment *zero* or *one* of the serial port library includes. + // If none of these includes are uncommented, Serial will be used. + // + //#include // NeoSerial or NeoSerial1 Interrupt-style processing + #include // <-- DEFAULT. Two specific pins required + //#include // AltSoftSerial with Interrupt-style processing (see docs) + //#include // Any pins, only @ 9600, 19200 or 38400 baud + //#include // NOT RECOMMENDED! + + #if defined( SoftwareSerial_h ) + #define SS_TYPE SoftwareSerial + #warning SoftwareSerial is NOT RECOMMENDED. Use AltSoftSerial or NeoSWSerial instead. + + #if defined( NMEAGPS_INTERRUPT_PROCESSING ) + #error You cannot use SoftwareSerial with INTERRUPT_PROCESSING. Use NeoSWSerial or NeoICSerial instead. + #endif + + #elif defined( NeoSWSerial_h ) + #define SS_TYPE NeoSWSerial + + #elif defined( AltSoftSerial_h ) + #define SS_TYPE AltSoftSerial + #define RX_PIN -1 // doesn't matter because it only works... + #define TX_PIN -1 // ...on two specific pins + + #if defined( NMEAGPS_INTERRUPT_PROCESSING ) + #error You cannot use AltSoftSerial with INTERRUPT_PROCESSING. Use NeoICSerial instead. + #endif + + #elif defined( NeoICSerial_h ) + #define SS_TYPE NeoICSerial + #define RX_PIN -1 // doesn't matter because it only works... + #define TX_PIN -1 // ...on two specific pins + + #elif defined( NeoHWSerial_h ) + #define gpsPort NeoSerial + #define GPS_PORT_NAME "NeoSerial" + #warning Using Serial (actually NeoSerial) for GPS connection. + + #else + // No serial library files were included before this file, just use Serial. + #define gpsPort Serial + #define GPS_PORT_NAME "Serial" + #warning Using Serial for GPS connection. + + // You will see this warning if you want to use Serial for the GPS, because no + // software serial port libraries were included. That is a good choice. + // + // To use a different serial port for GPS device, you must include a serial header + // before "#include GPSport.h" in the INO. It may be simpler to replace the + // entire contents of this file with your own declarations. Follow the + // instructions above for declaring your own "gpsPort" variable. Everything else + // in this file should be deleted. See Installation instructions for more + // information. + #endif +#endif + + +#ifdef SS_TYPE + + //--------------------------------------------------------------- + // The current Board (an Uno?) does not have an extra serial port. + // Use a software serial library to listen to the GPS device. + // You should expect to get some RX errors, which may + // prevent getting fix data every second. YMMV. + + // Default Arduino RX pin number that is connected to the GPS TX pin + #ifndef RX_PIN + #define RX_PIN 4 + #endif + + // Default Arduino TX pin number that is connected to the GPS RX pin + #ifndef TX_PIN + #define TX_PIN 3 + #endif + + SS_TYPE gpsPort( RX_PIN, TX_PIN ); + + // A little preprocessor magic to get a nice string + #define xstr(x) str(x) + #define str(x) #x + #define GPS_PORT_NAME \ + xstr(SS_TYPE) "( RX pin " xstr(RX_PIN) \ + ", TX pin " xstr(TX_PIN) " )" + + #ifdef NEOGPS_USE_SERIAL1 + // If you *really* want to do this, or you just happened to include + // a software serial library header for something else, you're + // better off *not* including this file. Just declare + // your own gpsPort in your INO file. + + #error You should be using Serial1 for the GPS device. \ + Software serial libraries are very inefficient and unreliable when \ + used for GPS communications! + #endif + +#endif + +//------------------------------------------------------------ +// When NeoHWSerial is used, none of the built-in HardwareSerial +// variables can be used: Serial, Serial1, Serial2 and Serial3 +// *cannot* be used. Instead, you must use the corresponding +// NeoSerial, NeoSerial1, NeoSerial2 or NeoSerial3. This define +// is used to substitute the appropriate Serial variable in +// all debug prints. + +#ifdef NeoHWSerial_h + #define DEBUG_PORT NeoSerial +#else + #define DEBUG_PORT Serial // default for most sketches +#endif + +// End of guessing game. +//------------------------ + +#endif diff --git a/software/firmware/libraries/NeoGPS/src/Location.cpp b/software/firmware/libraries/NeoGPS/src/Location.cpp new file mode 100644 index 0000000..10eb453 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/src/Location.cpp @@ -0,0 +1,137 @@ +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . + +#include "Location.h" + +using namespace NeoGPS; + +//--------------------------------------------------------------------- +// Calculate dLon with integers, less one bit to avoid overflow +// (360 * 1e7 = 3600000000, which is too big). +// Retains precision when points are close together. + +int32_t safeDLon( int32_t p2, int32_t p1 ) +{ + int32_t dLonL; + int32_t halfDLon = (p2/2 - p1/2); + if (halfDLon < -1800000000L/2) { + dLonL = (p2 + 1800000000L) - (p1 - 1800000000L); + } else if (1800000000L/2 < halfDLon) { + dLonL = (p2 - 1800000000L) - (p1 + 1800000000L); + } else { + dLonL = p2 - p1; + } + return dLonL; + +} // safeDLon + +//--------------------------------------------------------------------- + +float Location_t::DistanceRadians + ( const Location_t & p1, const Location_t & p2 ) +{ + int32_t dLonL = safeDLon( p2.lon(), p1.lon() ); + int32_t dLatL = p2.lat() - p1.lat(); + + if ((abs(dLatL)+abs(dLonL)) < 1000) { + // VERY close together. Just use equirect approximation with precise integers. + // This is not needed for accuracy (that I can measure), but it is + // a quicker calculation. + return EquirectDistanceRadians( p1, p2 ); + } + + // Haversine calculation from http://www.movable-type.co.uk/scripts/latlong.html + float dLat = dLatL * RAD_PER_DEG * LOC_SCALE; + float haverDLat = sin(dLat/2.0); + haverDLat *= haverDLat; // squared + + float dLon = dLonL * RAD_PER_DEG * LOC_SCALE; + float haverDLon = sin(dLon/2.0); + haverDLon *= haverDLon; // squared + + float lat1 = p1.latF(); + lat1 *= RAD_PER_DEG; + float lat2 = p2.latF(); + lat2 *= RAD_PER_DEG; + float a = haverDLat + cos(lat1) * cos(lat2) * haverDLon; + + float c = 2 * atan2( sqrt(a), sqrt(1-a) ); + + return c; + +} // DistanceRadians + +//--------------------------------------------------------------------- + +float Location_t::EquirectDistanceRadians + ( const Location_t & p1, const Location_t & p2 ) +{ + // Equirectangular calculation from http://www.movable-type.co.uk/scripts/latlong.html + + float dLat = (p2.lat() - p1.lat()) * RAD_PER_DEG * LOC_SCALE; + float dLon = safeDLon( p2.lon(), p1.lon() ) * RAD_PER_DEG * LOC_SCALE; + float x = dLon * cos( p1.lat() * RAD_PER_DEG * LOC_SCALE + dLat/2 ); + return sqrt( x*x + dLat*dLat ); + +} // EquirectDistanceRadians + +//--------------------------------------------------------------------- + +float Location_t::BearingTo( const Location_t & p1, const Location_t & p2 ) +{ + int32_t dLonL = safeDLon( p2.lon(), p1.lon() ); + float dLon = dLonL * RAD_PER_DEG * LOC_SCALE; + int32_t dLatL = p2.lat() - p1.lat(); + float lat1 = p1.lat() * RAD_PER_DEG * LOC_SCALE; + float cosLat1 = cos( lat1 ); + float x, y, bearing; + + if ((abs(dLatL)+abs(dLonL)) < 1000) { + // VERY close together. Just use equirect approximation with precise integers. + x = dLonL * cosLat1; + y = dLatL; + bearing = PI/2.0 - atan2(y, x); + + } else { + float lat2 = p2.lat() * RAD_PER_DEG * LOC_SCALE; + float cosLat2 = cos(lat2); + y = sin(dLon) * cosLat2; + x = cosLat1 * sin(lat2) - sin(lat1) * cosLat2 * cos(dLon); + bearing = atan2(y, x); + } + + if (bearing < 0.0) + bearing += TWO_PI; + + return bearing; + +} // BearingTo + +//--------------------------------------------------------------------- + +void Location_t::OffsetBy( float distR, float bearingR ) +{ + float lat1 = lat() * RAD_PER_DEG * LOC_SCALE; + float newLat = asin( sin(lat1)*cos(distR) + + cos(lat1)*sin(distR)*cos(bearingR) ); + float dLon = atan2( sin(bearingR)*sin(distR)*cos(lat1), + cos(distR)-sin(lat1)*sin(newLat)); + + _lat = (newLat / (RAD_PER_DEG * LOC_SCALE)); + _lon += (dLon / (RAD_PER_DEG * LOC_SCALE)); + +} // OffsetBy \ No newline at end of file diff --git a/software/firmware/libraries/NeoGPS/src/Location.h b/software/firmware/libraries/NeoGPS/src/Location.h new file mode 100644 index 0000000..8b0e054 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/src/Location.h @@ -0,0 +1,128 @@ +#ifndef NEOGPS_LOCATION_H +#define NEOGPS_LOCATION_H + +#include + +#include "NeoGPS_cfg.h" + +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . + +class NMEAGPS; + +namespace NeoGPS { + +class Location_t +{ +public: + CONST_CLASS_DATA float LOC_SCALE = 1.0e-7; + + Location_t() {} + Location_t( int32_t lat, int32_t lon ) + : _lat(lat), _lon(lon) + {} + Location_t( float lat, float lon ) + : _lat(lat / LOC_SCALE), _lon(lon / LOC_SCALE) + {} + Location_t( double lat, double lon ) + : _lat(lat / LOC_SCALE), _lon(lon / LOC_SCALE) + {} + + int32_t lat() const { return _lat; }; + void lat( int32_t l ) { _lat = l; }; + float latF() const { return ((float) lat()) * LOC_SCALE; }; + void latF( float v ) { _lat = v * LOC_SCALE; }; + + int32_t lon() const { return _lon; }; + void lon( int32_t l ) { _lon = l; }; + float lonF() const { return ((float) lon()) * LOC_SCALE; }; + void lonF( float v ) { _lon = v * LOC_SCALE; }; + + void init() { _lat = _lon = 0; }; + + CONST_CLASS_DATA float EARTH_RADIUS_KM = 6371.0088; + CONST_CLASS_DATA float RAD_PER_DEG = PI / 180.0; + CONST_CLASS_DATA float DEG_PER_RAD = 180.0 / PI; + CONST_CLASS_DATA float MI_PER_KM = 0.621371; + + //----------------------------------- + // Distance calculations + + static float DistanceKm( const Location_t & p1, const Location_t & p2 ) + { + return DistanceRadians( p1, p2 ) * EARTH_RADIUS_KM; + } + float DistanceKm( const Location_t & p2 ) + { return DistanceKm( *this, p2 ); } + + static float DistanceMiles( const Location_t & p1, const Location_t & p2 ) + { + return DistanceRadians( p1, p2 ) * EARTH_RADIUS_KM * MI_PER_KM; + } + float DistanceMiles( const Location_t & p2 ) + { return DistanceMiles( *this, p2 ); } + + static float DistanceRadians( const Location_t & p1, const Location_t & p2 ); + float DistanceRadians( const Location_t & p2 ) + { return DistanceRadians( *this, p2 ); } + + static float EquirectDistanceRadians + ( const Location_t & p1, const Location_t & p2 ); + float EquirectDistanceRadians( const Location_t & p2 ) + { return EquirectDistanceRadians( *this, p2 ); } + + static float EquirectDistanceKm( const Location_t & p1, const Location_t & p2 ) + { + return EquirectDistanceRadians( p1, p2 ) * EARTH_RADIUS_KM; + } + float EquirectDistanceKm( const Location_t & p2 ) const + { return EquirectDistanceKm( *this, p2 ); } + + static float EquirectDistanceMiles( const Location_t & p1, const Location_t & p2 ) + { + return EquirectDistanceRadians( p1, p2 ) * EARTH_RADIUS_KM * MI_PER_KM; + } + float EquirectDistanceMiles( const Location_t & p2 ) const + { return EquirectDistanceMiles( *this, p2 ); } + + //----------------------------------- + // Bearing calculations + + static float BearingTo( const Location_t & p1, const Location_t & p2 ); // radians + float BearingTo( const Location_t & p2 ) const // radians + { return BearingTo( *this, p2 ); } + + static float BearingToDegrees( const Location_t & p1, const Location_t & p2 ) + { return BearingTo( p1, p2 ) * DEG_PER_RAD; } + float BearingToDegrees( const Location_t & p2 ) const // radians + { return BearingToDegrees( *this, p2 ); } + + //----------------------------------- + // Offset a location (note distance is in radians, not degrees) + void OffsetBy( float distR, float bearingR ); + +//private: //--------------------------------------- + friend class NMEAGPS; // This does not work?!? + + int32_t _lat; // degrees * 1e7, negative is South + int32_t _lon; // degrees * 1e7, negative is West + +} NEOGPS_PACKED; + +} // NeoGPS + +#endif \ No newline at end of file diff --git a/software/firmware/libraries/NeoGPS/src/NMEAGPS.cpp b/software/firmware/libraries/NeoGPS/src/NMEAGPS.cpp new file mode 100644 index 0000000..33d9ce5 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/src/NMEAGPS.cpp @@ -0,0 +1,2071 @@ +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . + +#include "NMEAGPS.h" + +#include + +// Check configurations + +#if defined( GPS_FIX_LOCATION_DMS ) & \ + !defined( NMEAGPS_PARSING_SCRATCHPAD ) + + // The fractional part of the NMEA minutes can have 5 significant figures. + // This requires more temporary storage than is available in the DMS_t. + #error You must enable NMEAGPS_PARSING_SCRATCHPAD in NMEAGPS_cfg.h when GPS_FIX_LOCATION_DMS is enabled in GPSfix_cfg.h! + +#endif + +#ifndef CR + #define CR ((char)13) +#endif +#ifndef LF + #define LF ((char)10) +#endif + +//---------------------------------------------------------------- +// Parse a single character as HEX and returns byte value. + +inline static uint8_t parseHEX(char a) +{ + a |= 0x20; // make it lowercase + if (('a' <= a) && (a <= 'f')) + return a - 'a' + 10; + else + return a - '0'; +} + +//---------------------------------------------------------------- +// Format lower nybble of value as HEX and returns character. + +static char formatHex( uint8_t val ) +{ + val &= 0x0F; + return (val >= 10) ? ((val - 10) + 'A') : (val + '0'); +} + +//---------------------------------------------------------------- + +inline uint8_t to_binary(uint8_t value) +{ + uint8_t high = (value >> 4); + uint8_t low = (value & 0x0f); + return ((high << 3) + (high << 1) + low); +} + +//---------------------------------------------------------------- + +NMEAGPS::NMEAGPS() +{ + #ifdef NMEAGPS_STATS + statistics.init(); + #endif + + data_init(); + + reset(); +} + +//---------------------------------------------------------------- +// Prepare internal members to receive data from sentence fields. + +void NMEAGPS::sentenceBegin() +{ + if (intervalComplete()) { + // GPS quiet time is over, this is the start of a new interval. + + #if defined(NMEAGPS_TIMESTAMP_FROM_INTERVAL) & \ + ( defined(GPS_FIX_DATE) | defined(GPS_FIX_TIME) ) + _IntervalStart = micros(); + #endif + + intervalComplete( false ); + + #ifdef NMEAGPS_PARSE_SATELLITES + sat_count = 0; + #endif + } + + crc = 0; + nmeaMessage = NMEA_UNKNOWN; + rxState = NMEA_RECEIVING_HEADER; + chrCount = 0; + comma_needed( false ); + + #ifdef NMEAGPS_PARSE_PROPRIETARY + proprietary = false; + + #ifdef NMEAGPS_SAVE_MFR_ID + mfr_id[0] = + mfr_id[1] = + mfr_id[2] = 0; + #endif + #endif + + #ifdef NMEAGPS_SAVE_TALKER_ID + talker_id[0] = + talker_id[1] = 0; + #endif + +} // sentenceBegin + +//---------------------------------------------------------------- +// All fields from a sentence have been parsed. + +void NMEAGPS::sentenceOk() +{ + // Terminate the last field with a comma if the parser needs it. + if (comma_needed()) { + comma_needed( false ); + chrCount++; + parseField(','); + } + + #ifdef NMEAGPS_STATS + statistics.ok++; + #endif + + // This implements coherency. + intervalComplete( intervalCompleted() ); + + if (intervalComplete()) { + // GPS quiet time now + + } + + reset(); +} + +//---------------------------------------------------------------- +// There was something wrong with the sentence. + +void NMEAGPS::sentenceInvalid() +{ + // All the values are suspect. Start over. + m_fix.valid.init(); + nmeaMessage = NMEA_UNKNOWN; + + reset(); +} + +//---------------------------------------------------------------- +// The sentence is well-formed, but is an unrecognized type + +void NMEAGPS::sentenceUnrecognized() +{ + nmeaMessage = NMEA_UNKNOWN; + + reset(); +} + +//---------------------------------------------------------------- + +void NMEAGPS::headerReceived() +{ + NMEAGPS_INIT_FIX(m_fix); + fieldIndex = 1; + chrCount = 0; + rxState = NMEA_RECEIVING_DATA; +} + +//---------------------------------------------------------------- +// Process one character of an NMEA GPS sentence. + +NMEAGPS::decode_t NMEAGPS::decode( char c ) +{ + #ifdef NMEAGPS_STATS + statistics.chars++; + #endif + + decode_t res = DECODE_CHR_OK; + + if (c == '$') { // Always restarts + sentenceBegin(); + + } else if (rxState == NMEA_RECEIVING_DATA) { //--------------------------- + // Receive complete sentence + + if (c == '*') { // Line finished, CRC follows + rxState = NMEA_RECEIVING_CRC; + chrCount = 0; + + } else if ((' ' <= c) && (c <= '~')) { // Normal data character + + crc ^= c; // accumulate CRC as the chars come in... + + if (!parseField( c )) + sentenceInvalid(); + else if (c == ',') { + // Start the next field + comma_needed( false ); + fieldIndex++; + chrCount = 0; + } else + chrCount++; + + // This is an undocumented option. It could be useful + // for testing, but all real devices will output a CS. + #ifdef NMEAGPS_CS_OPTIONAL + } else if ((c == CR) || (c == LF)) { // Line finished, no CRC + sentenceOk(); + res = DECODE_COMPLETED; + #endif + + } else { // Invalid char + sentenceInvalid(); + res = DECODE_CHR_INVALID; + } + + + } else if (rxState == NMEA_RECEIVING_HEADER) { //------------------------ + + // The first field is the sentence type. It will be used + // later by the virtual /parseField/. + + crc ^= c; // accumulate CRC as the chars come in... + + decode_t cmd_res = parseCommand( c ); + + if (cmd_res == DECODE_CHR_OK) { + chrCount++; + } else if (cmd_res == DECODE_COMPLETED) { + headerReceived(); + } else { // DECODE_CHR_INVALID + sentenceUnrecognized(); + } + + + } else if (rxState == NMEA_RECEIVING_CRC) { //--------------------------- + bool err; + uint8_t nybble = parseHEX( c ); + + if (chrCount == 0) { + chrCount++; + err = ((crc >> 4) != nybble); + } else { // chrCount == 1 + err = ((crc & 0x0F) != nybble); + if (!err) { + sentenceOk(); + res = DECODE_COMPLETED; + } + } + + if (err) { + #ifdef NMEAGPS_STATS + statistics.errors++; + #endif + sentenceInvalid(); + } + + } else if (rxState == NMEA_IDLE) { //--------------------------- + // Reject non-start characters + + res = DECODE_CHR_INVALID; + nmeaMessage = NMEA_UNKNOWN; + } + + return res; + +} // decode + +//---------------------------------------------------------------- + +NMEAGPS::decode_t NMEAGPS::handle( uint8_t c ) +{ + decode_t res = decode( c ); + + if (res == DECODE_COMPLETED) { + storeFix(); + + } else if ((NMEAGPS_FIX_MAX == 0) && _available() && !is_safe()) { + // No buffer, and m_fix is was modified by the last char + overrun( true ); + } + + return res; + +} // handle + +//---------------------------------------------------------------- + +void NMEAGPS::storeFix() +{ + // Room for another fix? + + bool room = ((NMEAGPS_FIX_MAX == 0) && !_available()) || + ((NMEAGPS_FIX_MAX > 0) && (_available() < NMEAGPS_FIX_MAX)); + + if (!room) { + overrun( true ); + + if (keepNewestFixes) { + + #if NMEAGPS_FIX_MAX > 0 + + // Write over the oldest fix (_firstFix), so "pop" it off the front. + _firstFix++; + if (_firstFix >= NMEAGPS_FIX_MAX) + _firstFix = 0; + + // this new one is not available until the interval is complete + _fixesAvailable--; + + #else + // Write over the one and only fix. It may not be complete. + _fixesAvailable = false; + #endif + + // Now there's room! + room = true; + } + } + + if (room) { + // YES, save it. + // Note: If FIX_MAX == 0, this just marks _fixesAvailable = true. + + #if NMEAGPS_FIX_MAX > 0 + if (merging == EXPLICIT_MERGING) { + // Accumulate all sentences + buffer[ _currentFix ] |= fix(); + } + #endif + + if ((merging == NO_MERGING) || intervalComplete()) { + + #if defined(NMEAGPS_TIMESTAMP_FROM_INTERVAL) & \ + defined(GPS_FIX_TIME) + + // If this new fix is the start of a second, save the + // interval start time as the start of this UTC second. + + #if NMEAGPS_FIX_MAX > 0 + gps_fix & currentFix = buffer[ _currentFix ]; + #else + gps_fix & currentFix = m_fix; + #endif + + if (currentFix.valid.time && (currentFix.dateTime_cs == 0)) + UTCsecondStart( _IntervalStart ); + + #endif + + #if NMEAGPS_FIX_MAX > 0 + + if (merging != EXPLICIT_MERGING) + buffer[ _currentFix ] = fix(); + + _currentFix++; + if (_currentFix >= NMEAGPS_FIX_MAX) + _currentFix = 0; + + if (_fixesAvailable < NMEAGPS_FIX_MAX) + _fixesAvailable++; + + #else // FIX_MAX == 0 + _fixesAvailable = true; + #endif + + } + } + +} // storeFix + +//---------------------------------------------------------------- +// NMEA Sentence strings (alphabetical) + +#if defined(NMEAGPS_PARSE_GGA) | defined(NMEAGPS_RECOGNIZE_ALL) + static const char gga[] __PROGMEM = "GGA"; +#endif +#if defined(NMEAGPS_PARSE_GLL) | defined(NMEAGPS_RECOGNIZE_ALL) + static const char gll[] __PROGMEM = "GLL"; +#endif +#if defined(NMEAGPS_PARSE_GSA) | defined(NMEAGPS_RECOGNIZE_ALL) + static const char gsa[] __PROGMEM = "GSA"; +#endif +#if defined(NMEAGPS_PARSE_GST) | defined(NMEAGPS_RECOGNIZE_ALL) + static const char gst[] __PROGMEM = "GST"; +#endif +#if defined(NMEAGPS_PARSE_GSV) | defined(NMEAGPS_RECOGNIZE_ALL) + static const char gsv[] __PROGMEM = "GSV"; +#endif +#if defined(NMEAGPS_PARSE_RMC) | defined(NMEAGPS_RECOGNIZE_ALL) + static const char rmc[] __PROGMEM = "RMC"; +#endif +#if defined(NMEAGPS_PARSE_VTG) | defined(NMEAGPS_RECOGNIZE_ALL) + static const char vtg[] __PROGMEM = "VTG"; +#endif +#if defined(NMEAGPS_PARSE_ZDA) | defined(NMEAGPS_RECOGNIZE_ALL) + static const char zda[] __PROGMEM = "ZDA"; +#endif + +static const char * const std_nmea[] __PROGMEM = + { + #if defined(NMEAGPS_PARSE_GGA) | defined(NMEAGPS_RECOGNIZE_ALL) + gga, + #endif + #if defined(NMEAGPS_PARSE_GLL) | defined(NMEAGPS_RECOGNIZE_ALL) + gll, + #endif + #if defined(NMEAGPS_PARSE_GSA) | defined(NMEAGPS_RECOGNIZE_ALL) + gsa, + #endif + #if defined(NMEAGPS_PARSE_GST) | defined(NMEAGPS_RECOGNIZE_ALL) + gst, + #endif + #if defined(NMEAGPS_PARSE_GSV) | defined(NMEAGPS_RECOGNIZE_ALL) + gsv, + #endif + #if defined(NMEAGPS_PARSE_RMC) | defined(NMEAGPS_RECOGNIZE_ALL) + rmc, + #endif + #if defined(NMEAGPS_PARSE_VTG) | defined(NMEAGPS_RECOGNIZE_ALL) + vtg, + #endif + #if defined(NMEAGPS_PARSE_ZDA) | defined(NMEAGPS_RECOGNIZE_ALL) + zda + #endif + }; + +// If you change this message table structure, be sure to update the optimizations in +// ::string_for and ::parseCommand for !defined( NMEAGPS_DERIVED_TYPES ) + +const NMEAGPS::msg_table_t NMEAGPS::nmea_msg_table __PROGMEM = + { + NMEAGPS::NMEA_FIRST_MSG, + (const msg_table_t *) NULL, + sizeof(std_nmea)/sizeof(std_nmea[0]), + std_nmea + }; + +//---------------------------------------------------------------- +// For NMEA, start with talker or manufacture ID + +NMEAGPS::decode_t NMEAGPS::parseCommand( char c ) +{ + if (c == ',') { + // End of field, did we get a sentence type yet? + return + (nmeaMessage == NMEA_UNKNOWN) ? + DECODE_CHR_INVALID : + DECODE_COMPLETED; + } + + #ifdef NMEAGPS_PARSE_PROPRIETARY + if ((chrCount == 0) && (c == 'P')) { + // Starting a proprietary message... + proprietary = true; + return DECODE_CHR_OK; + } + #endif + + uint8_t cmdCount = chrCount; + + #ifdef NMEAGPS_PARSE_PROPRIETARY + if (proprietary) { + + // Next three chars are the manufacturer ID + if (chrCount < 4) { + #ifdef NMEAGPS_SAVE_MFR_ID + mfr_id[chrCount-1] = c; + #endif + + #ifdef NMEAGPS_PARSE_MFR_ID + if (!parseMfrID( c )) + return DECODE_CHR_INVALID; + #endif + + return DECODE_CHR_OK; + } + + cmdCount -= 4; + + } else + #endif + { // standard + + // First two chars are talker ID + if (chrCount < 2) { + #ifdef NMEAGPS_SAVE_TALKER_ID + talker_id[chrCount] = c; + #endif + + #ifdef NMEAGPS_PARSE_TALKER_ID + if (!parseTalkerID( c )) + return DECODE_CHR_INVALID; + #endif + + return DECODE_CHR_OK; + } + + cmdCount -= 2; + } + + // The remaining characters are the message type. + + const msg_table_t *msgs = msg_table(); + + return parseCommand( msgs, cmdCount, c ); + +} // parseCommand + +//---------------------------------------------------------------- +// Determine the NMEA sentence type + +NMEAGPS::decode_t NMEAGPS::parseCommand + ( const msg_table_t *msgs, uint8_t cmdCount, char c ) +{ + for (;;) { + #ifdef NMEAGPS_DERIVED_TYPES + uint8_t table_size = pgm_read_byte( &msgs->size ); + uint8_t msg_offset = pgm_read_byte( &msgs->offset ); + bool check_this_table = true; + #else + const uint8_t table_size = sizeof(std_nmea)/sizeof(std_nmea[0]); + const uint8_t msg_offset = NMEA_FIRST_MSG; + const bool check_this_table = true; + #endif + decode_t res = DECODE_CHR_INVALID; + uint8_t entry; + + if (nmeaMessage == NMEA_UNKNOWN) { + // We're just starting + entry = 0; + + } else if ((msg_offset <= nmeaMessage) && (nmeaMessage < msg_offset+table_size)) { + // In range of this table, pick up where we left off + entry = nmeaMessage - msg_offset; + } + #ifdef NMEAGPS_DERIVED_TYPES + else + check_this_table = false; + #endif + + if (check_this_table) { + uint8_t i = entry; + + #if !defined( NMEAGPS_DERIVED_TYPES ) + const char * const *table = std_nmea; + #else + const char * const *table = (const char * const *) pgm_read_ptr( &msgs->table ); + #endif + const char * table_i = (const char * ) pgm_read_ptr( &table[i] ); + + for (;;) { + char rc = pgm_read_byte( &table_i[cmdCount] ); + if (c == rc) { + // ok so far... + entry = i; + res = DECODE_CHR_OK; + break; + } + + if (c < rc) { + // Alphabetical rejection, check next table + break; + } + + // Ok to check another entry in this table + uint8_t next_msg = i+1; + if (next_msg >= table_size) { + // No more entries in this table. + break; + } + + // See if the next entry starts with the same characters. + const char *table_next = (const char *) pgm_read_ptr( &table[next_msg] ); + + for (uint8_t j = 0; j < cmdCount; j++) + if (pgm_read_byte( &table_i[j] ) != pgm_read_byte( &table_next[j] )) { + // Nope, a different start to this entry + break; + } + i = next_msg; + table_i = table_next; + } + } + + if (res == DECODE_CHR_INVALID) { + + #ifdef NMEAGPS_DERIVED_TYPES + msgs = (const msg_table_t *) pgm_read_ptr( &msgs->previous ); + if (msgs) { + // Try the current character in the previous table + continue; + } // else + // No more tables, chr is invalid. + #endif + + } else { + // This entry is good so far. + nmeaMessage = (nmea_msg_t) (entry + msg_offset); + } + + return res; + } + +} // parseCommand + +//---------------------------------------------------------------- + +const __FlashStringHelper *NMEAGPS::string_for( nmea_msg_t msg ) const +{ + if (msg == NMEA_UNKNOWN) + return F("UNK"); + + #ifdef NMEAGPS_DERIVED_TYPES + const msg_table_t *msgs = msg_table(); + #endif + + for (;;) { + #ifdef NMEAGPS_DERIVED_TYPES + uint8_t table_size = pgm_read_byte( &msgs->size ); + uint8_t msg_offset = pgm_read_byte( &msgs->offset ); + #else + const uint8_t table_size = sizeof(std_nmea)/sizeof(std_nmea[0]); + const uint8_t msg_offset = NMEA_FIRST_MSG; + #endif + + if ((msg_offset <= msg) && (msg < msg_offset+table_size)) { + // In range of this table + #if !defined( NMEAGPS_DERIVED_TYPES ) + const char * const *table = std_nmea; + #else + const char * const *table = (const char * const *) pgm_read_ptr( &msgs->table ); + #endif + const uint8_t i = ((uint8_t)msg) - msg_offset; + const char * table_i = (const char *) pgm_read_ptr( &table[i] ); + return (const __FlashStringHelper *) table_i; + } + + #ifdef NMEAGPS_DERIVED_TYPES + // Try the previous table + msgs = (const msg_table_t *) pgm_read_ptr( &msgs->previous ); + if (msgs) + continue; + #endif + + return (const __FlashStringHelper *) NULL; + } + +} // string_for + +//---------------------------------------------------------------- + +bool NMEAGPS::parseField(char chr) +{ + switch (nmeaMessage) { + + #if defined(NMEAGPS_PARSE_GGA) + case NMEA_GGA: return parseGGA( chr ); + #endif + + #if defined(NMEAGPS_PARSE_GLL) + case NMEA_GLL: return parseGLL( chr ); + #endif + + #if defined(NMEAGPS_PARSE_GSA) + case NMEA_GSA: return parseGSA( chr ); + #endif + + #if defined(NMEAGPS_PARSE_GST) + case NMEA_GST: return parseGST( chr ); + #endif + + #if defined(NMEAGPS_PARSE_GSV) + case NMEA_GSV: return parseGSV( chr ); + #endif + + #if defined(NMEAGPS_PARSE_RMC) + case NMEA_RMC: return parseRMC( chr ); + #endif + + #if defined(NMEAGPS_PARSE_VTG) + case NMEA_VTG: return parseVTG( chr ); + #endif + + #if defined(NMEAGPS_PARSE_ZDA) + case NMEA_ZDA: return parseZDA( chr ); + #endif + + default: + break; + } + + return true; + +} // parseField + +//---------------------------------------------------------------- + +bool NMEAGPS::parseGGA( char chr ) +{ + #ifdef NMEAGPS_PARSE_GGA + switch (fieldIndex) { + case 1: return parseTime( chr ); + PARSE_LOC(2); + case 6: return parseFix( chr ); + case 7: return parseSatellites( chr ); + case 8: return parseHDOP( chr ); + case 9: return parseAlt( chr ); + case 11: return parseGeoidHeight( chr ); + } + #endif + + return true; + +} // parseGGA + +//---------------------------------------------------------------- + +bool NMEAGPS::parseGLL( char chr ) +{ + #ifdef NMEAGPS_PARSE_GLL + switch (fieldIndex) { + PARSE_LOC(1); + case 5: return parseTime( chr ); + case 7: return parseFix( chr ); + } + #endif + + return true; + +} // parseGLL + +//---------------------------------------------------------------- + +bool NMEAGPS::parseGSA( char chr ) +{ + #ifdef NMEAGPS_PARSE_GSA + + switch (fieldIndex) { + case 2: + if (chrCount == 0) { + if ((chr == '2') || (chr == '3')) { + m_fix.status = gps_fix::STATUS_STD; + m_fix.valid.status = true; + } else if (chr == '1') { + m_fix.status = gps_fix::STATUS_NONE; + m_fix.valid.status = true; + } else if (validateChars() | validateFields()) + sentenceInvalid(); + } + break; + + case 15: + #if !defined( NMEAGPS_PARSE_GSV ) + // Finalize the satellite count (for the fix *and* the satellites array) + if (chrCount == 0) { + if (sat_count >= NMEAGPS_MAX_SATELLITES) + sat_count = NMEAGPS_MAX_SATELLITES-1; + #if defined( NMEAGPS_PARSE_SATELLITES ) && \ + !defined( NMEAGPS_PARSE_GGA ) + m_fix.valid.satellites = (m_fix.satellites > 0); + #endif + } + #endif + return parsePDOP( chr ); + + case 16: return parseHDOP( chr ); + case 17: return parseVDOP( chr ); + #if defined(GPS_FIX_VDOP) & !defined(NMEAGPS_COMMA_NEEDED) + #error When GSA and VDOP are enabled, you must define NMEAGPS_COMMA_NEEDED in NMEAGPS_cfg.h! + #endif + + #ifdef NMEAGPS_PARSE_SATELLITES + + // It's not clear how this sentence relates to GSV and GGA. + // GSA only allows 12 satellites, while GSV allows any number. + // GGA just says how many are used to calculate a fix. + + // GGA shall have priority over GSA with respect to populating the + // satellites field. Don't use the number of satellite ID fields + // to set the satellites field if GGA is enabled. + + // GSV shall have priority over GSA with respect to populating the + // satellites array. Ignore the satellite ID fields if GSV is enabled. + + case 1: break; // allows "default:" case for SV fields + + #ifndef NMEAGPS_PARSE_GSV + case 3: + if (chrCount == 0) { + sat_count = 0; + #ifndef NMEAGPS_PARSE_GGA + NMEAGPS_INVALIDATE( satellites ); + m_fix.satellites = 0; + #endif + comma_needed( true ); + } + default: + if (chr == ',') { + if (chrCount > 0) { + sat_count++; + #ifndef NMEAGPS_PARSE_GGA + m_fix.satellites++; + #endif + } + } else if (sat_count < NMEAGPS_MAX_SATELLITES) + parseInt( satellites[ sat_count ].id, chr ); + break; + #endif + #endif + } + #endif + + return true; + +} // parseGSA + +//---------------------------------------------------------------- + +bool NMEAGPS::parseGST( char chr ) +{ + #ifdef NMEAGPS_PARSE_GST + switch (fieldIndex) { + case 1: return parseTime( chr ); + case 6: return parse_lat_err( chr ); + case 7: return parse_lon_err( chr ); + case 8: return parse_alt_err( chr ); + } + #endif + + return true; + +} // parseGST + +//---------------------------------------------------------------- + +bool NMEAGPS::parseGSV( char chr ) +{ + #if defined(NMEAGPS_PARSE_GSV) & defined(NMEAGPS_PARSE_SATELLITES) + #if !defined(NMEAGPS_PARSE_GSA) & !defined(NMEAGPS_PARSE_GGA) + if ((sat_count == 0) && (fieldIndex == 1) && (chrCount == 0)) { + NMEAGPS_INVALIDATE( satellites ); + m_fix.satellites = 0; + } + #endif + + if (sat_count < NMEAGPS_MAX_SATELLITES) { + if (fieldIndex >= 4) { + + switch (fieldIndex % 4) { + #ifdef NMEAGPS_PARSE_SATELLITE_INFO + case 0: parseInt( satellites[sat_count].id , chr ); break; + case 1: parseInt( satellites[sat_count].elevation, chr ); break; + case 2: + if (chr != ',') + parseInt( satellites[sat_count].azimuth, chr ); + else { + // field 3 can be omitted, do some things now + satellites[sat_count].tracked = false; + sat_count++; + } + break; + case 3: + if (chr != ',') { + uint8_t snr = satellites[sat_count-1].snr; + parseInt( snr, chr ); + satellites[sat_count-1].snr = snr; + comma_needed( true ); + } else { + satellites[sat_count-1].tracked = (chrCount != 0); + #if !defined(NMEAGPS_PARSE_GSA) & !defined(NMEAGPS_PARSE_GGA) + if (satellites[sat_count-1].tracked) { + m_fix.satellites++; + m_fix.valid.satellites = true; // but there may be more + } + #endif + } + break; + #else + case 0: + if (chr != ',') + parseInt( satellites[sat_count].id, chr ); + else { + sat_count++; + #if !defined(NMEAGPS_PARSE_GSA) & !defined(NMEAGPS_PARSE_GGA) + m_fix.satellites++; + m_fix.valid.satellites = true; // but there may be more + #endif + } + break; + case 3: + #if !defined(NMEAGPS_PARSE_GSA) & !defined(NMEAGPS_PARSE_GGA) + if ((chr == ',') && (chrCount != 0)) { + m_fix.satellites++; // tracked + m_fix.valid.satellites = true; // but there may be more + } + #endif + break; + #endif + } + } + } + #endif + + return true; + +} // parseGSV + +//---------------------------------------------------------------- + +bool NMEAGPS::parseRMC( char chr ) +{ + #ifdef NMEAGPS_PARSE_RMC + switch (fieldIndex) { + case 1: return parseTime ( chr ); + case 2: return parseFix ( chr ); + PARSE_LOC(3); + case 7: return parseSpeed ( chr ); + case 8: return parseHeading( chr ); + case 9: return parseDDMMYY ( chr ); + // case 12: return parseFix ( chr ); ublox only! + } + #endif + + return true; + +} // parseRMC + +//---------------------------------------------------------------- + +bool NMEAGPS::parseVTG( char chr ) +{ + #ifdef NMEAGPS_PARSE_VTG + switch (fieldIndex) { + case 1: return parseHeading( chr ); + case 5: return parseSpeed( chr ); + case 9: return parseFix( chr ); + } + #endif + + return true; + +} // parseVTG + +//---------------------------------------------------------------- + +bool NMEAGPS::parseZDA( char chr ) +{ + #ifdef NMEAGPS_PARSE_ZDA + switch (fieldIndex) { + case 1: return parseTime( chr ); + + #ifdef GPS_FIX_DATE + case 2: + if (chrCount == 0) { + NMEAGPS_INVALIDATE( date ); + if (validateFields()) + comma_needed( true ); + } + parseInt( m_fix.dateTime.date , chr ); + + if (validateFields() && (chrCount > 0) && (chr == ',')) { + uint8_t days = + pgm_read_byte + ( &NeoGPS::time_t::days_in[ m_fix.dateTime.date ] ); + if ((m_fix.dateTime.date < 1) || (days < m_fix.dateTime.date)) + sentenceInvalid(); + } + break; + + case 3: + if (validateFields() && (chrCount == 0)) + comma_needed( true ); + + parseInt( m_fix.dateTime.month, chr ); + + if (validateFields() && (chrCount > 0) && (chr == ',') && + ((m_fix.dateTime.month < 1) || (12 < m_fix.dateTime.month))) + sentenceInvalid(); + break; + + case 4: + if (validateFields() && (chrCount == 0)) + comma_needed( true ); + + if (chr != ',') { + // year is BCD until terminating comma. + // This essentially keeps the last two digits + if (validateChars() && !isdigit( chr )) + sentenceInvalid(); + else if (chrCount == 0) { + comma_needed( true ); + m_fix.dateTime.year = (chr - '0'); + } else + m_fix.dateTime.year = (m_fix.dateTime.year << 4) + (chr - '0'); + + } else { + // Terminating comma received, convert from BCD to decimal + m_fix.dateTime.year = to_binary( m_fix.dateTime.year ); + if (validateFields() && + ( ((chrCount != 2) && (chrCount != 4)) || + (99 < m_fix.dateTime.year) )) + sentenceInvalid(); + else + m_fix.valid.date = true; + } + break; + #endif + } + #endif + + return true; + +} // parseZDA + +//---------------------------------------------------------------- + +bool NMEAGPS::parseTime(char chr) +{ + #ifdef GPS_FIX_TIME + switch (chrCount) { + case 0: + NMEAGPS_INVALIDATE( time ); + + if (chr != ',') { + if (validateChars()) + comma_needed( true ); + if (validateChars() && !isdigit(chr)) + sentenceInvalid(); + else + m_fix.dateTime.hours = (chr - '0')*10; + } + break; + + case 1: + if (validateChars() && !isdigit(chr)) + sentenceInvalid(); + else + m_fix.dateTime.hours += (chr - '0'); + + if (validateFields() && (23 < m_fix.dateTime.hours)) + sentenceInvalid(); + break; + + case 2: + if (validateChars() && !isdigit(chr)) + sentenceInvalid(); + else + m_fix.dateTime.minutes = (chr - '0')*10; + break; + case 3: + if (validateChars() && !isdigit(chr)) + sentenceInvalid(); + else + m_fix.dateTime.minutes += (chr - '0'); + if (validateFields() && (59 < m_fix.dateTime.minutes)) + sentenceInvalid(); + break; + + case 4: + if (validateChars() && !isdigit(chr)) + sentenceInvalid(); + else + m_fix.dateTime.seconds = (chr - '0')*10; + break; + case 5: + if (validateChars() && !isdigit(chr)) + sentenceInvalid(); + else + m_fix.dateTime.seconds += (chr - '0'); + if (validateFields() && (59 < m_fix.dateTime.seconds)) + sentenceInvalid(); + break; + + case 6: + if (validateChars() && (chr != '.')) + sentenceInvalid(); + break; + + case 7: + if (validateChars() && !isdigit(chr)) + sentenceInvalid(); + else + m_fix.dateTime_cs = (chr - '0')*10; + break; + case 8: + if (validateChars() && !isdigit(chr)) + sentenceInvalid(); + else + m_fix.dateTime_cs += (chr - '0'); + if (validateFields() && (99 < m_fix.dateTime_cs)) + sentenceInvalid(); + else + m_fix.valid.time = true; + break; + + default: + if (validateChars() && !isdigit( chr ) && (chr != ',')) + sentenceInvalid(); + break; + } + #endif + + return true; + +} // parseTime + +//---------------------------------------------------------------- + +bool NMEAGPS::parseDDMMYY( char chr ) +{ + #ifdef GPS_FIX_DATE + switch (chrCount) { + case 0: + NMEAGPS_INVALIDATE( date ); + + if (chr != ',') { + if (validateChars()) + comma_needed( true ); + if (validateChars() && !isdigit( chr )) + sentenceInvalid(); + else + m_fix.dateTime.date = (chr - '0')*10; + } + break; + + case 1: + if (validateChars() && !isdigit( chr )) + sentenceInvalid(); + else { + m_fix.dateTime.date += (chr - '0'); + + if (validateFields()) { + uint8_t days = + pgm_read_byte + ( &NeoGPS::time_t::days_in[m_fix.dateTime.date] ); + if ((m_fix.dateTime.date < 1) || (days < m_fix.dateTime.date)) + sentenceInvalid(); + } + } + break; + + case 2: + if (validateChars() && !isdigit( chr )) + sentenceInvalid(); + else + m_fix.dateTime.month = (chr - '0')*10; + break; + case 3: + if (validateChars() && !isdigit( chr )) + sentenceInvalid(); + else { + m_fix.dateTime.month += (chr - '0'); + + if (validateFields() && + ((m_fix.dateTime.month < 1) || (12 < m_fix.dateTime.month))) + sentenceInvalid(); + } + break; + + case 4: + if (validateChars() && !isdigit( chr )) + sentenceInvalid(); + else + m_fix.dateTime.year = (chr - '0')*10; + break; + case 5: + if (validateChars() && !isdigit( chr )) + sentenceInvalid(); + else { + m_fix.dateTime.year += (chr - '0'); + m_fix.valid.date = true; + } + break; + + case 6: + if (validateChars() && (chr != ',')) + sentenceInvalid(); + break; + } + #endif + + return true; + +} // parseDDMMYY + +//---------------------------------------------------------------- + +bool NMEAGPS::parseFix( char chr ) +{ + if (chrCount == 0) { + NMEAGPS_INVALIDATE( status ); + bool ok = true; + if ((chr == '1') || (chr == 'A')) + m_fix.status = gps_fix::STATUS_STD; + else if ((chr == '0') || (chr == 'N') || (chr == 'V')) + m_fix.status = gps_fix::STATUS_NONE; + else if ((chr == '2') || (chr == 'D')) + m_fix.status = gps_fix::STATUS_DGPS; + else if (chr == '3') + m_fix.status = gps_fix::STATUS_PPS; + else if (chr == '4') + m_fix.status = gps_fix::STATUS_RTK_FIXED; + else if (chr == '5') + m_fix.status = gps_fix::STATUS_RTK_FLOAT; + else if ((chr == '6') || (chr == 'E')) + m_fix.status = gps_fix::STATUS_EST; + else { + if (validateChars() | validateFields()) { + sentenceInvalid(); + } + ok = false; + } + if (ok) + m_fix.valid.status = true; + } if ((validateChars() | validateFields()) && ((chrCount > 1) || (chr != ','))) { + sentenceInvalid(); + } + + return true; + +} // parseFix + +//---------------------------------------------------------------- + +bool NMEAGPS::parseFloat + ( gps_fix::whole_frac & val, char chr, uint8_t max_decimal ) +{ + bool done = false; + + if (chrCount == 0) { + val.init(); + comma_needed( true ); + decimal = 0; + negative = (chr == '-'); + if (negative) return done; + } + + if (chr == ',') { + // End of field, make sure it's scaled up + if (!decimal) + decimal = 1; + if (val.frac) + while (decimal++ <= max_decimal) + val.frac *= 10; + if (negative) { + val.frac = -val.frac; + val.whole = -val.whole; + } + done = true; + } else if (chr == '.') { + decimal = 1; + } else if (validateChars() && !isdigit(chr)) { + sentenceInvalid(); + } else if (!decimal) { + val.whole = val.whole*10 + (chr - '0'); + } else if (decimal++ <= max_decimal) { + val.frac = val.frac*10 + (chr - '0'); + } + + return done; + +} // parseFloat + +//---------------------------------------------------------------- + +bool NMEAGPS::parseFloat( uint16_t & val, char chr, uint8_t max_decimal ) +{ + bool done = false; + + if (chrCount == 0) { + val = 0; + comma_needed( true ); + decimal = 0; + negative = (chr == '-'); + if (negative) return done; + } + + if (chr == ',') { + if (val) + while (decimal++ <= max_decimal) + val *= 10; + if (negative) + val = -val; + done = true; + } else if (chr == '.') { + decimal = 1; + } else if (validateChars() && !isdigit(chr)) { + sentenceInvalid(); + } else if (decimal++ <= max_decimal) { + val = val*10 + (chr - '0'); + } + + return done; + +} // parseFloat + +//---------------------------------------------------------------- + +#ifdef GPS_FIX_LOCATION_DMS + + static void finalizeDMS( uint32_t min_frac, DMS_t & dms ) + { + // To convert from fractional minutes (hundred thousandths) to + // seconds_whole and seconds_frac, + // + // seconds = min_frac * 60/100000 + // = min_frac * 0.0006 + + #ifdef __AVR__ + // Fixed point conversion factor 0.0006 * 2^26 = 40265 + const uint32_t to_seconds_E26 = 40265UL; + + uint32_t secs_E26 = min_frac * to_seconds_E26; + uint8_t secs = secs_E26 >> 26; + uint32_t remainder_E26 = secs_E26 - (((uint32_t) secs) << 26); + + // thousandths = (rem_E26 * 1000) >> 26; + // = (rem_E26 * 125) >> 23; // 1000 = (125 << 3) + // = ((rem_E26 >> 8) * 125) >> 15; // avoid overflow + // = (((rem_E26 >> 8) * 125) >> 8) >> 7; // final shift 15 in two steps + // = ((((rem_E26 >> 8) * 125) >> 8) + 72) >> 7; + // // round up + uint16_t frac_x1000 = ((((remainder_E26 >> 8) * 125UL) >> 8) + 64) >> 7; + + #else // not __AVR__ + + min_frac *= 6UL; + uint32_t secs = min_frac / 10000UL; + uint16_t frac_x1000 = (min_frac - (secs * 10000UL) + 5) / 10; + + #endif + + // Rounding up can yield a frac of 1000/1000ths. Carry into whole. + if (frac_x1000 >= 1000) { + frac_x1000 -= 1000; + secs += 1; + } + dms.seconds_whole = secs; + dms.seconds_frac = frac_x1000; + + } // finalizeDMS + +#endif + +//................................................. +// From http://www.hackersdelight.org/divcMore.pdf + +static uint32_t divu3( uint32_t n ) +{ + #ifdef __AVR__ + uint32_t q = (n >> 2) + (n >> 4); // q = n*0.0101 (approx). + q = q + (q >> 4); // q = n*0.01010101. + q = q + (q >> 8); + q = q + (q >> 16); + + uint32_t r = n - q*3; // 0 <= r <= 15. + return q + (11*r >> 5); // Returning q + r/3. + #else + return n/3; + #endif +} + +//................................................. +// Parse lat/lon dddmm.mmmm fields + +bool NMEAGPS::parseDDDMM + ( + #if defined( GPS_FIX_LOCATION ) + int32_t & val, + #endif + #if defined( GPS_FIX_LOCATION_DMS ) + DMS_t & dms, + #endif + char chr + ) +{ + bool done = false; + + #if defined( GPS_FIX_LOCATION ) | defined( GPS_FIX_LOCATION_DMS ) + + if (chrCount == 0) { + #ifdef GPS_FIX_LOCATION + val = 0; + #endif + #ifdef GPS_FIX_LOCATION_DMS + dms.init(); + #endif + decimal = 0; + comma_needed( true ); + } + + if ((chr == '.') || ((chr == ',') && !decimal)) { + // Now we know how many digits are in degrees; all but the last two. + // Switch from BCD (digits) to binary minutes. + decimal = 1; + #ifdef GPS_FIX_LOCATION + uint8_t *valBCD = (uint8_t *) &val; + #else + uint8_t *valBCD = (uint8_t *) &dms; + #endif + uint8_t deg = to_binary( valBCD[1] ); + if (valBCD[2] != 0) + deg += 100; // only possible if abs(longitude) >= 100.0 degrees + + // Convert val to minutes + uint8_t min = to_binary( valBCD[0] ); + + if (validateFields() && (min >= 60)) + sentenceInvalid(); + else { + #ifdef GPS_FIX_LOCATION + val = (deg * 60) + min; + #endif + #ifdef GPS_FIX_LOCATION_DMS + dms.degrees = deg; + dms.minutes = min; + scratchpad.U4 = 0; + #endif + } + + if (chr == '.') return done; + } + + if (chr == ',') { + // If the last chars in ".mmmmmm" were not received, + // force the value into its final state. + + #ifdef GPS_FIX_LOCATION_DMS + if (decimal <= 5) { + if (decimal == 5) + scratchpad.U4 *= 10; + else if (decimal == 4) + scratchpad.U4 *= 100; + else if (decimal == 3) + scratchpad.U4 *= 1000; + else if (decimal == 2) + scratchpad.U4 *= 10000; + + finalizeDMS( scratchpad.U4, dms ); + } + #endif + + #ifdef GPS_FIX_LOCATION + if (decimal == 4) + val *= 100; + else if (decimal == 5) + val *= 10; + else if (decimal == 6) + ; + else if (decimal > 6) + return true; // already converted at decimal==7 + else if (decimal == 3) + val *= 1000; + else if (decimal == 2) + val *= 10000; + else if (decimal == 1) + val *= 100000; + + // Convert minutes x 1000000 to degrees x 10000000. + val += divu3(val*2 + 1); // same as 10 * ((val+30)/60) without trunc + #endif + + done = true; + + } else if (validateChars() && !isdigit(chr)) { + sentenceInvalid(); + + } else if (!decimal) { + // BCD until *after* decimal point + + #ifdef GPS_FIX_LOCATION + val = (val<<4) | (chr - '0'); + #else + uint32_t *val = (uint32_t *) &dms; + *val = (*val<<4) | (chr - '0'); + #endif + + } else { + + decimal++; + + #ifdef GPS_FIX_LOCATION_DMS + if (decimal <= 6) { + scratchpad.U4 = scratchpad.U4 * 10 + (chr - '0'); + if (decimal == 6) + finalizeDMS( scratchpad.U4, dms ); + } + #endif + + #ifdef GPS_FIX_LOCATION + if (decimal <= 6) { + + val = val*10 + (chr - '0'); + + } else if (decimal == 7) { + + // Convert now, while we still have the 6th decimal digit + val += divu3(val*2 + 1); // same as 10 * ((val+30)/60) without trunc + if (chr >= '9') + val += 2; + else if (chr >= '4') + val += 1; + } + #endif + } + + #endif + + return done; + +} // parseDDDMM + +//---------------------------------------------------------------- + +bool NMEAGPS::parseLat( char chr ) +{ + #if defined( GPS_FIX_LOCATION ) | defined( GPS_FIX_LOCATION_DMS ) + if (chrCount == 0) { + group_valid = (chr != ','); + if (group_valid) + NMEAGPS_INVALIDATE( location ); + } + + if (group_valid) { + + if (parseDDDMM + ( + #if defined( GPS_FIX_LOCATION ) + m_fix.location._lat, + #endif + #if defined( GPS_FIX_LOCATION_DMS ) + m_fix.latitudeDMS, + #endif + chr + )) { + + if (validateFields()) { + + #if defined( GPS_FIX_LOCATION ) + if (m_fix.location._lat > 900000000L) + sentenceInvalid(); + #endif + #if defined( GPS_FIX_LOCATION_DMS ) + if ((m_fix.latitudeDMS.degrees > 90) || + ((m_fix.latitudeDMS.degrees == 90) && + ( (m_fix.latitudeDMS.minutes > 0) || + (m_fix.latitudeDMS.seconds_whole > 0) || + (m_fix.latitudeDMS.seconds_frac > 0) ))) + sentenceInvalid(); + #endif + } + } + } + #endif + + return true; + +} // parseLatitude + +//---------------------------------------------------------------- + +bool NMEAGPS::parseNS( char chr ) +{ + #if defined( GPS_FIX_LOCATION ) | defined( GPS_FIX_LOCATION_DMS ) + if (group_valid) { + + if (chrCount == 0) { + + // First char can only be 'N' or 'S' + if (chr == 'S') { + #ifdef GPS_FIX_LOCATION + m_fix.location._lat = -m_fix.location._lat; + #endif + #ifdef GPS_FIX_LOCATION_DMS + m_fix.latitudeDMS.hemisphere = SOUTH_H; + #endif + } else if ((validateChars() | validateFields()) && (chr != 'N')) { + sentenceInvalid(); + } + + // Second char can only be ',' + } else if ((validateChars() | validateFields()) && + ((chrCount > 1) || (chr != ','))) { + sentenceInvalid(); + } + } + #endif + + return true; + +} // parseNS + +//---------------------------------------------------------------- + +bool NMEAGPS::parseLon( char chr ) +{ + #if defined( GPS_FIX_LOCATION ) | defined( GPS_FIX_LOCATION_DMS ) + if ((chr == ',') && (chrCount == 0)) + group_valid = false; + + if (group_valid) { + + if (parseDDDMM + ( + #if defined( GPS_FIX_LOCATION ) + m_fix.location._lon, + #endif + #if defined( GPS_FIX_LOCATION_DMS ) + m_fix.longitudeDMS, + #endif + chr + )) { + + if (validateFields()) { + + #if defined( GPS_FIX_LOCATION ) + if (m_fix.location._lon > 1800000000L) + sentenceInvalid(); + #endif + #if defined( GPS_FIX_LOCATION_DMS ) + if ((m_fix.longitudeDMS.degrees > 180) || + ((m_fix.longitudeDMS.degrees == 180) && + ( (m_fix.longitudeDMS.minutes > 0) || + (m_fix.longitudeDMS.seconds_whole > 0) || + (m_fix.longitudeDMS.seconds_frac > 0) ))) + sentenceInvalid(); + #endif + } + } + } + #endif + + return true; + +} // parseLon + +//---------------------------------------------------------------- + +bool NMEAGPS::parseEW( char chr ) +{ + #if defined( GPS_FIX_LOCATION ) | defined( GPS_FIX_LOCATION_DMS ) + if (group_valid) { + + if (chrCount == 0) { + m_fix.valid.location = true; // assumption + + // First char can only be 'W' or 'E' + if (chr == 'W') { + #ifdef GPS_FIX_LOCATION + m_fix.location._lon = -m_fix.location._lon; + #endif + #ifdef GPS_FIX_LOCATION_DMS + m_fix.longitudeDMS.hemisphere = WEST_H; + #endif + } else if ((validateChars() | validateFields()) && (chr != 'E')) { + sentenceInvalid(); + } + + // Second char can only be ',' + } else if ((validateChars() | validateFields()) && + ((chrCount > 1) || (chr != ','))) { + sentenceInvalid(); + } + } + #endif + + return true; + +} // parseEW + +//---------------------------------------------------------------- + +bool NMEAGPS::parseSpeed( char chr ) +{ + #ifdef GPS_FIX_SPEED + if (chrCount == 0) + NMEAGPS_INVALIDATE( speed ); + if (parseFloat( m_fix.spd, chr, 3 )) { + + if (validateFields() && m_fix.valid.speed && negative) + sentenceInvalid(); + else + m_fix.valid.speed = (chrCount != 0); + } + #endif + + return true; + +} // parseSpeed + +//---------------------------------------------------------------- + +bool NMEAGPS::parseHeading( char chr ) +{ + #ifdef GPS_FIX_HEADING + if (chrCount == 0) + NMEAGPS_INVALIDATE( heading ); + if (parseFloat( m_fix.hdg, chr, 2 )) { + + if (validateFields() && m_fix.valid.heading && + (negative || (m_fix.hdg.whole >= 360))) + sentenceInvalid(); + else + m_fix.valid.heading = (chrCount != 0); + } + #endif + + return true; + +} // parseHeading + +//---------------------------------------------------------------- + +bool NMEAGPS::parseAlt(char chr ) +{ + #ifdef GPS_FIX_ALTITUDE + if (chrCount == 0) + NMEAGPS_INVALIDATE( altitude ); + if (parseFloat( m_fix.alt, chr, 2 )) { + if (validateFields() && (m_fix.alt.whole < -1000)) + sentenceInvalid(); + else + m_fix.valid.altitude = (chrCount != 0); + } + #endif + + return true; + +} // parseAlt + +//---------------------------------------------------------------- + +bool NMEAGPS::parseGeoidHeight( char chr ) +{ + #ifdef GPS_FIX_GEOID_HEIGHT + if (chrCount == 0) + NMEAGPS_INVALIDATE( geoidHeight ); + if (parseFloat( m_fix.geoidHt, chr, 2 )) + m_fix.valid.geoidHeight = (chrCount != 0); + #endif + + return true; + +} // parseGeoidHeight + +//---------------------------------------------------------------- + +bool NMEAGPS::parseSatellites( char chr ) +{ + #ifdef GPS_FIX_SATELLITES + if (chrCount == 0) + NMEAGPS_INVALIDATE( satellites ); + + if (parseInt( m_fix.satellites, chr )) { + if (validateFields() && negative) + sentenceInvalid(); + else + m_fix.valid.satellites = true; + } + #endif + + return true; + +} // parseSatellites + +//---------------------------------------------------------------- + +bool NMEAGPS::parseHDOP( char chr ) +{ + #ifdef GPS_FIX_HDOP + if (chrCount == 0) + NMEAGPS_INVALIDATE( hdop ); + if (parseFloat( m_fix.hdop, chr, 3 )) { + if (validateFields() && negative) + sentenceInvalid(); + else + m_fix.valid.hdop = (chrCount != 0); + } + #endif + + return true; + +} // parseHDOP + +//---------------------------------------------------------------- + +bool NMEAGPS::parseVDOP( char chr ) +{ + #ifdef GPS_FIX_VDOP + if (chrCount == 0) + NMEAGPS_INVALIDATE( vdop ); + if (parseFloat( m_fix.vdop, chr, 3 )) { + if (validateFields() && negative) + sentenceInvalid(); + else + m_fix.valid.vdop = (chrCount != 0); + } + #endif + + return true; + +} // parseVDOP + +//---------------------------------------------------------------- + +bool NMEAGPS::parsePDOP( char chr ) +{ + #ifdef GPS_FIX_PDOP + if (chrCount == 0) + NMEAGPS_INVALIDATE( pdop ); + if (parseFloat( m_fix.pdop, chr, 3 )) { + if (validateFields() && negative) + sentenceInvalid(); + else + m_fix.valid.pdop = (chrCount != 0); + } + #endif + + return true; + +} // parsePDOP + +//---------------------------------------------------------------- + +static const uint16_t MAX_ERROR_CM = 2000; // 20m is a large STD error + +bool NMEAGPS::parse_lat_err( char chr ) +{ + #ifdef GPS_FIX_LAT_ERR + if (chrCount == 0) + NMEAGPS_INVALIDATE( lat_err ); + if (parseFloat( m_fix.lat_err_cm, chr, 2 )) { + if (validateFields() && + (negative || (m_fix.valid.alt_err > MAX_ERROR_CM))) + sentenceInvalid(); + else + m_fix.valid.lat_err = (chrCount != 0); + } + #endif + + return true; + +} // parse_lat_err + +//---------------------------------------------------------------- + +bool NMEAGPS::parse_lon_err( char chr ) +{ + #ifdef GPS_FIX_LON_ERR + if (chrCount == 0) + NMEAGPS_INVALIDATE( lon_err ); + if (parseFloat( m_fix.lon_err_cm, chr, 2 )) { + if (validateFields() && + (negative || (m_fix.valid.lon_err > MAX_ERROR_CM))) + sentenceInvalid(); + else + m_fix.valid.lon_err = (chrCount != 0); + } + #endif + + return true; + +} // parse_lon_err + +//---------------------------------------------------------------- + +bool NMEAGPS::parse_alt_err( char chr ) +{ + #ifdef GPS_FIX_ALT_ERR + if (chrCount == 0) + NMEAGPS_INVALIDATE( alt_err ); + if (parseFloat( m_fix.alt_err_cm, chr, 2 )) { + if (validateFields() && + (negative || (m_fix.valid.alt_err > MAX_ERROR_CM))) + sentenceInvalid(); + else + m_fix.valid.alt_err = (chrCount != 0); + } + #endif + + return true; + +} // parse_alt_err + +//---------------------------------------------------------------- + +const gps_fix NMEAGPS::read() +{ + gps_fix fix; + + if (_fixesAvailable) { + lock(); + + #if (NMEAGPS_FIX_MAX > 0) + _fixesAvailable--; + fix = buffer[ _firstFix ]; + if (merging == EXPLICIT_MERGING) + // Prepare to accumulate all fixes in an interval + buffer[ _firstFix ].init(); + if (++_firstFix >= NMEAGPS_FIX_MAX) + _firstFix = 0; + #else + if (is_safe()) { + _fixesAvailable = false; + fix = m_fix; + } + #endif + + unlock(); + } + + return fix; + +} // read + +//---------------------------------------------------------------- + +void NMEAGPS::poll( Stream *device, nmea_msg_t msg ) +{ + // Only the ublox documentation references talker ID "EI". + // Other manufacturer's devices use "II" and "GP" talker IDs for the GPQ sentence. + // However, "GP" is reserved for the GPS device, so it seems inconsistent + // to use that talker ID when requesting something from the GPS device. + + #if defined(NMEAGPS_PARSE_GGA) | defined(NMEAGPS_RECOGNIZE_ALL) + static const char gga[] __PROGMEM = "EIGPQ,GGA"; + #endif + #if defined(NMEAGPS_PARSE_GLL) | defined(NMEAGPS_RECOGNIZE_ALL) + static const char gll[] __PROGMEM = "EIGPQ,GLL"; + #endif + #if defined(NMEAGPS_PARSE_GSA) | defined(NMEAGPS_RECOGNIZE_ALL) + static const char gsa[] __PROGMEM = "EIGPQ,GSA"; + #endif + #if defined(NMEAGPS_PARSE_GST) | defined(NMEAGPS_RECOGNIZE_ALL) + static const char gst[] __PROGMEM = "EIGPQ,GST"; + #endif + #if defined(NMEAGPS_PARSE_GSV) | defined(NMEAGPS_RECOGNIZE_ALL) + static const char gsv[] __PROGMEM = "EIGPQ,GSV"; + #endif + #if defined(NMEAGPS_PARSE_RMC) | defined(NMEAGPS_RECOGNIZE_ALL) + static const char rmc[] __PROGMEM = "EIGPQ,RMC"; + #endif + #if defined(NMEAGPS_PARSE_VTG) | defined(NMEAGPS_RECOGNIZE_ALL) + static const char vtg[] __PROGMEM = "EIGPQ,VTG"; + #endif + #if defined(NMEAGPS_PARSE_ZDA) | defined(NMEAGPS_RECOGNIZE_ALL) + static const char zda[] __PROGMEM = "EIGPQ,ZDA"; + #endif + + static const char * const poll_msgs[] __PROGMEM = + { + #if defined(NMEAGPS_PARSE_GGA) | defined(NMEAGPS_RECOGNIZE_ALL) + gga, + #endif + #if defined(NMEAGPS_PARSE_GLL) | defined(NMEAGPS_RECOGNIZE_ALL) + gll, + #endif + #if defined(NMEAGPS_PARSE_GSA) | defined(NMEAGPS_RECOGNIZE_ALL) + gsa, + #endif + #if defined(NMEAGPS_PARSE_GST) | defined(NMEAGPS_RECOGNIZE_ALL) + gst, + #endif + #if defined(NMEAGPS_PARSE_GSV) | defined(NMEAGPS_RECOGNIZE_ALL) + gsv, + #endif + #if defined(NMEAGPS_PARSE_RMC) | defined(NMEAGPS_RECOGNIZE_ALL) + rmc, + #endif + #if defined(NMEAGPS_PARSE_VTG) | defined(NMEAGPS_RECOGNIZE_ALL) + vtg, + #endif + #if defined(NMEAGPS_PARSE_ZDA) | defined(NMEAGPS_RECOGNIZE_ALL) + zda + #endif + }; + + if ((NMEA_FIRST_MSG <= msg) && (msg <= NMEA_LAST_MSG)) { + const __FlashStringHelper * pollCmd = + (const __FlashStringHelper *) pgm_read_ptr( &poll_msgs[msg-NMEA_FIRST_MSG] ); + send_P( device, pollCmd ); + } + +} // poll + +//---------------------------------------------------------------- + +static void send_trailer( Stream *device, uint8_t crc ) +{ + device->print('*'); + + char hexDigit = formatHex( crc>>4 ); + device->print( hexDigit ); + + hexDigit = formatHex( crc ); + device->print( hexDigit ); + + device->print( CR ); + device->print( LF ); + +} // send_trailer + +//---------------------------------------------------------------- + +void NMEAGPS::send( Stream *device, const char *msg ) +{ + if (msg && *msg) { + if (*msg == '$') + msg++; + device->print('$'); + uint8_t sent_trailer = 0; + uint8_t crc = 0; + while (*msg) { + if ((*msg == '*') || (sent_trailer > 0)) + sent_trailer++; + else + crc ^= *msg; + device->print( *msg++ ); + } + + if (!sent_trailer) + send_trailer( device, crc ); + } + +} // send + +//---------------------------------------------------------------- + +void NMEAGPS::send_P( Stream *device, const __FlashStringHelper *msg ) +{ + if (msg) { + const char *ptr = (const char *)msg; + char chr = pgm_read_byte(ptr++); + + device->print('$'); + if (chr == '$') + chr = pgm_read_byte(ptr++); + uint8_t sent_trailer = 0; + uint8_t crc = 0; + while (chr) { + if ((chr == '*') || (sent_trailer > 0)) + sent_trailer++; + else + crc ^= chr; + device->print( chr ); + + chr = pgm_read_byte(ptr++); + } + + if (!sent_trailer) + send_trailer( device, crc ); + } + +} // send_P diff --git a/software/firmware/libraries/NeoGPS/src/NMEAGPS.h b/software/firmware/libraries/NeoGPS/src/NMEAGPS.h new file mode 100644 index 0000000..6e28372 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/src/NMEAGPS.h @@ -0,0 +1,340 @@ +#ifndef NMEAGPS_H +#define NMEAGPS_H + +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . + +#include "CosaCompat.h" + +#include +#ifdef __AVR__ + #include +#endif + +#include "GPSfix.h" +#include "NMEAGPS_cfg.h" + +//------------------------------------------------------ +// +// NMEA 0183 Parser for generic GPS Modules. +// +// As bytes are received from the device, they affect the +// internal FSM and set various members of the current /fix/. +// As multiple sentences are received, they are (optionally) +// merged into a single fix. When the last sentence in a time +// interval (usually 1 second) is received, the fix is stored +// in the (optional) buffer of fixes. +// +// Only these NMEA messages are parsed: +// GGA, GLL, GSA, GST, GSV, RMC, VTG, and ZDA. + +class NMEAGPS +{ + NMEAGPS & operator =( const NMEAGPS & ); + NMEAGPS( const NMEAGPS & ); + +public: + + NMEAGPS(); + + //....................................................................... + // NMEA standard message types (aka "sentences") + + enum nmea_msg_t { + NMEA_UNKNOWN, + + #if defined(NMEAGPS_PARSE_GGA) | defined(NMEAGPS_RECOGNIZE_ALL) + NMEA_GGA, + #endif + + #if defined(NMEAGPS_PARSE_GLL) | defined(NMEAGPS_RECOGNIZE_ALL) + NMEA_GLL, + #endif + + #if defined(NMEAGPS_PARSE_GSA) | defined(NMEAGPS_RECOGNIZE_ALL) + NMEA_GSA, + #endif + + #if defined(NMEAGPS_PARSE_GST) | defined(NMEAGPS_RECOGNIZE_ALL) + NMEA_GST, + #endif + + #if defined(NMEAGPS_PARSE_GSV) | defined(NMEAGPS_RECOGNIZE_ALL) + NMEA_GSV, + #endif + + #if defined(NMEAGPS_PARSE_RMC) | defined(NMEAGPS_RECOGNIZE_ALL) + NMEA_RMC, + #endif + + #if defined(NMEAGPS_PARSE_VTG) | defined(NMEAGPS_RECOGNIZE_ALL) + NMEA_VTG, + #endif + + #if defined(NMEAGPS_PARSE_ZDA) | defined(NMEAGPS_RECOGNIZE_ALL) + NMEA_ZDA, + #endif + + NMEAMSG_END // a bookend that tells how many enums there were + }; + + CONST_CLASS_DATA nmea_msg_t NMEA_FIRST_MSG = (nmea_msg_t) (NMEA_UNKNOWN+1); + CONST_CLASS_DATA nmea_msg_t NMEA_LAST_MSG = (nmea_msg_t) (NMEAMSG_END-1); + + //======================================================================= + // FIX-ORIENTED methods: available, read, overrun and handle + //======================================================================= + // The typical sketch should have something like this in loop(): + // + // while (gps.available( Serial1 )) { + // gps_fix fix = gps.read(); + // if (fix.valid.location) { + // ... + // } + // } + + //....................................................................... + // The available(...) functions return the number of *fixes* that + // are available to be "read" from the fix buffer. The GPS port + // object is passed in so a char can be read if port.available(). + + uint8_t available( Stream & port ) + { + if (processing_style == PS_POLLING) + while (port.available()) + handle( port.read() ); + return _available(); + } + uint8_t available() const volatile { return _available(); }; + + //....................................................................... + // Return the next available fix. When no more fixes + // are available, it returns an empty fix. + + const gps_fix read(); + + //....................................................................... + // The OVERRUN flag is set whenever a fix is not read by the time + // the next update interval starts. You must clear it when you + // detect the condition. + + bool overrun() const { return _overrun; } + void overrun( bool val ) { _overrun = val; } + + //....................................................................... + // As characters are processed, they can be categorized as + // INVALID (not part of this protocol), OK (accepted), + // or COMPLETED (end-of-message). + + enum decode_t { DECODE_CHR_INVALID, DECODE_CHR_OK, DECODE_COMPLETED }; + + //....................................................................... + // Process one character, possibly saving a buffered fix. + // It implements merging and coherency. + // This can be called from an ISR. + + decode_t handle( uint8_t c ); + + //======================================================================= + // CHARACTER-ORIENTED methods: decode, fix and is_safe + //======================================================================= + // + // *** MOST APPLICATIONS SHOULD USE THE FIX-ORIENTED METHODS *** + // + // Using `decode` is only necessary if you want finer control + // on how fix information is filtered and merged. + // + // Process one character of an NMEA GPS sentence. The internal state + // machine tracks what part of the sentence has been received. As the + // sentence is received, members of the /fix/ structure are updated. + // This character-oriented method *does not* buffer any fixes, and + // /read()/ will always return an empty fix. + // + // @return DECODE_COMPLETED when a sentence has been completely received. + + NMEAGPS_VIRTUAL decode_t decode( char c ); + + //....................................................................... + // Current fix accessor. + // *** MOST APPLICATIONS SHOULD USE read() TO GET THE CURRENT FIX *** + // /fix/ will be constantly changing as characters are received. + // + // For example, fix().longitude() may return nonsense data if + // characters for that field are currently being processed in /decode/. + + gps_fix & fix() { return m_fix; }; + + // NOTE: /is_safe/ *must* be checked before accessing members of /fix/. + // If you need access to the current /fix/ at any time, you should + // use the FIX-ORIENTED methods. + + //....................................................................... + // Determine whether the members of /fix/ are "currently" safe. + // It will return true when a complete sentence and the CRC characters + // have been received (or after a CR if no CRC is present). + // It will return false after a new sentence starts. + + bool is_safe() const volatile { return (rxState == NMEA_IDLE); } + + // NOTE: When INTERRUPT_PROCESSING is enabled, is_safe() + // and fix() could change at any time (i.e., they should be + // considered /volatile/). + + //======================================================================= + // DATA MEMBER accessors and mutators + //======================================================================= + + //....................................................................... + // Convert a nmea_msg_t to a PROGMEM string. + // Useful for printing the sentence type instead of a number. + // This can return "UNK" if the message is not a valid number. + + const __FlashStringHelper *string_for( nmea_msg_t msg ) const; + + //....................................................................... + // Most recent NMEA sentence type received. + + enum nmea_msg_t nmeaMessage NEOGPS_BF(8); + + //....................................................................... + // Storage for Talker and Manufacturer IDs + + #ifdef NMEAGPS_SAVE_TALKER_ID + char talker_id[2]; + #endif + + #ifdef NMEAGPS_SAVE_MFR_ID + char mfr_id[3]; + #endif + + //....................................................................... + // Various parsing statistics + + #ifdef NMEAGPS_STATS + struct statistics_t { + uint32_t ok; // count of successfully parsed sentences + uint32_t errors; // NMEA checksum or other message errors + uint32_t chars; + void init() + { + ok = 0L; + errors = 0L; + chars = 0L; + } + } statistics; + #endif + + //....................................................................... + // SATELLITE VIEW array + + #ifdef NMEAGPS_PARSE_SATELLITES + struct satellite_view_t + { + uint8_t id; + #ifdef NMEAGPS_PARSE_SATELLITE_INFO + uint8_t elevation; // 0..99 deg + uint16_t azimuth; // 0..359 deg + uint8_t snr NEOGPS_BF(7); // 0..99 dBHz + bool tracked NEOGPS_BF(1); + #endif + } NEOGPS_PACKED; + + satellite_view_t satellites[ NMEAGPS_MAX_SATELLITES ]; + uint8_t sat_count; // in the above array + + bool satellites_valid() const { return (sat_count >= m_fix.satellites); } + #endif + + //....................................................................... + // Reset the parsing process. + // This is used internally after a CS error, or could be used + // externally to abort processing if it has been too long + // since any data was received. + + void reset() + { + rxState = NMEA_IDLE; + } + + //======================================================================= + // CORRELATING Arduino micros() WITH UTC. + //======================================================================= + + #if defined(NMEAGPS_TIMESTAMP_FROM_PPS) | \ + defined(NMEAGPS_TIMESTAMP_FROM_INTERVAL) + protected: + uint32_t _UTCsecondStart; + #if defined(NMEAGPS_TIMESTAMP_FROM_INTERVAL) & \ + ( defined(GPS_FIX_DATE) | defined(GPS_FIX_TIME) ) + uint32_t _IntervalStart; // quiet time just ended + #endif + public: + + // The micros() value when the current UTC second started + uint32_t UTCsecondStart() const + { lock(); + uint32_t ret = _UTCsecondStart; + unlock(); + return ret; + }; + void UTCsecondStart( uint32_t us ) { _UTCsecondStart = us; }; + + // The elapsed time since the start of the current UTC second + uint32_t UTCus() const { return micros() - UTCsecondStart(); }; + uint32_t UTCms() const { return UTCus() / 1000UL; }; + + // If you have attached a Pin Change interrupt routine to the PPS pin: + // + // const int PPSpin = 5; + // void PPSisr() { gps.UTCsecondStart( micros() ); }; + // void setup() + // { + // attachInterrupt( digitalPinToInterrupt(PPSpin), PPSisr, RISING ); + // } + // + // If you are using an Input Capture pin, calculate the elapsed + // microseconds since the capture time (based on the TIMER + // frequency): + // + // void savePPSus() // called as an ISR or from a test in loop + // { + // uint32_t elapsedUS = (currentCount - captureCount) * countUS; + // gps.UTCsecondStart( micros() - elapsedUS ); + // } + #endif + + //======================================================================= + // COMMUNICATING WITH THE GPS DEVICE: poll, send and send_P + //======================================================================= + + //....................................................................... + // Request the specified NMEA sentence. Not all devices will respond. + + static void poll( Stream *device, nmea_msg_t msg ); + + //....................................................................... + // Send a message to the GPS device. + // The '$' is optional, and the '*' and CS will be added automatically. + + static void send( Stream *device, const char *msg ); + static void send_P( Stream *device, const __FlashStringHelper *msg ); + + #include "NMEAGPSprivate.h" + +} NEOGPS_PACKED; + +#endif diff --git a/software/firmware/libraries/NeoGPS/src/NMEAGPS_cfg.h b/software/firmware/libraries/NeoGPS/src/NMEAGPS_cfg.h new file mode 100644 index 0000000..c20bdef --- /dev/null +++ b/software/firmware/libraries/NeoGPS/src/NMEAGPS_cfg.h @@ -0,0 +1,338 @@ +#ifndef NMEAGPS_CFG_H +#define NMEAGPS_CFG_H + +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . + +#include "GPSfix_cfg.h" + +//------------------------------------------------------ +// Enable/disable the parsing of specific sentences. +// +// Configuring out a sentence prevents it from being recognized; it +// will be completely ignored. (See also NMEAGPS_RECOGNIZE_ALL, below) +// +// FYI: Only RMC and ZDA contain date information. Other +// sentences contain time information. Both date and time are +// required if you will be doing time_t-to-clock_t operations. + +#define NMEAGPS_PARSE_GGA +//#define NMEAGPS_PARSE_GLL +//#define NMEAGPS_PARSE_GSA +//#define NMEAGPS_PARSE_GSV +//#define NMEAGPS_PARSE_GST +#define NMEAGPS_PARSE_RMC +//#define NMEAGPS_PARSE_VTG +//#define NMEAGPS_PARSE_ZDA + +//------------------------------------------------------ +// Select which sentence is sent *last* by your GPS device +// in each update interval. This can be used by your sketch +// to determine when the GPS quiet time begins, and thus +// when you can perform "some" time-consuming operations. + +#define LAST_SENTENCE_IN_INTERVAL NMEAGPS::NMEA_RMC + +// NOTE: For PUBX-only configs, use +// (NMEAGPS::nmea_msg_t)(NMEAGPS::NMEA_LAST_MSG+1) +// +// If the NMEA_LAST_SENTENCE_IN_INTERVAL is not chosen +// correctly, GPS data may be lost because the sketch +// takes too long elsewhere when this sentence is received. +// Also, fix members may contain information from different +// time intervals (i.e., they are not coherent). +// +// If you don't know which sentence is the last one, +// use NMEAorder.ino to list them. You do not have to select +// the last sentence the device sends if you have disabled +// it. Just select the last sentence that you have *enabled*. + +//------------------------------------------------------ +// Choose how multiple sentences are merged into a fix: +// 1) No merging +// Each sentence fills out its own fix; there could be +// multiple sentences per interval. +// 2) EXPLICIT_MERGING +// All sentences in an interval are *safely* merged into one fix. +// NMEAGPS_FIX_MAX must be >= 1. +// An interval is defined by NMEA_LAST_SENTENCE_IN_INTERVAL. +// 3) IMPLICIT_MERGING +// All sentences in an interval are merged into one fix, with +// possible data loss. If a received sentence is rejected for +// any reason (e.g., a checksum error), all the values are suspect. +// The fix will be cleared; no members will be valid until new +// sentences are received and accepted. This uses less RAM. +// An interval is defined by NMEA_LAST_SENTENCE_IN_INTERVAL. +// Uncomment zero or one: + +#define NMEAGPS_EXPLICIT_MERGING +//#define NMEAGPS_IMPLICIT_MERGING + +#ifdef NMEAGPS_IMPLICIT_MERGING + #define NMEAGPS_MERGING NMEAGPS::IMPLICIT_MERGING + + // Nothing is done to the fix at the beginning of every sentence... + #define NMEAGPS_INIT_FIX(m) + + // ...but we invalidate one part when it starts to get parsed. It *may* get + // validated when the parsing is finished. + #define NMEAGPS_INVALIDATE(m) m_fix.valid.m = false + +#else + + #ifdef NMEAGPS_EXPLICIT_MERGING + #define NMEAGPS_MERGING NMEAGPS::EXPLICIT_MERGING + #else + #define NMEAGPS_MERGING NMEAGPS::NO_MERGING + #define NMEAGPS_NO_MERGING + #endif + + // When NOT accumulating (not IMPLICIT), invalidate the entire fix + // at the beginning of every sentence... + #define NMEAGPS_INIT_FIX(m) m.valid.init() + + // ...so the individual parts do not need to be invalidated as they are parsed + #define NMEAGPS_INVALIDATE(m) + +#endif + +#if ( defined(NMEAGPS_NO_MERGING) + \ + defined(NMEAGPS_IMPLICIT_MERGING) + \ + defined(NMEAGPS_EXPLICIT_MERGING) ) > 1 + #error Only one MERGING technique should be enabled in NMEAGPS_cfg.h! +#endif + +//------------------------------------------------------ +// Define the fix buffer size. The NMEAGPS object will hold on to +// this many fixes before an overrun occurs. This can be zero, +// but you have to be more careful about using gps.fix() structure, +// because it will be modified as characters are received. + +#define NMEAGPS_FIX_MAX 1 + +#if defined(NMEAGPS_EXPLICIT_MERGING) && (NMEAGPS_FIX_MAX == 0) + #error You must define FIX_MAX >= 1 to allow EXPLICIT merging in NMEAGPS_cfg.h +#endif + +//------------------------------------------------------ +// Define how fixes are dropped when the FIFO is full. +// true = the oldest fix will be dropped, and the new fix will be saved. +// false = the new fix will be dropped, and all old fixes will be saved. + +#define NMEAGPS_KEEP_NEWEST_FIXES true + +//------------------------------------------------------ +// Enable/Disable interrupt-style processing of GPS characters +// If you are using one of the NeoXXSerial libraries, +// to attachInterrupt, this must be defined. +// Otherwise, it must be commented out. + +//#define NMEAGPS_INTERRUPT_PROCESSING + +#ifdef NMEAGPS_INTERRUPT_PROCESSING + #define NMEAGPS_PROCESSING_STYLE NMEAGPS::PS_INTERRUPT +#else + #define NMEAGPS_PROCESSING_STYLE NMEAGPS::PS_POLLING +#endif + +//------------------------------------------------------ +// Enable/disable the talker ID, manufacturer ID and proprietary message processing. +// +// First, some background information. There are two kinds of NMEA sentences: +// +// 1. Standard NMEA sentences begin with "$ttccc", where +// "tt" is the talker ID, and +// "ccc" is the variable-length sentence type (i.e., command). +// +// For example, "$GPGLL,..." is a GLL sentence (Geographic Lat/Long) +// transmitted by talker "GP". This is the most common talker ID. Some +// devices may report "$GNGLL,..." when a mix of GPS and non-GPS +// satellites have been used to determine the GLL data. +// +// 2. Proprietary NMEA sentences (i.e., those unique to a particular +// manufacturer) begin with "$Pmmmccc", where +// "P" is the NMEA-defined prefix indicator for proprietary messages, +// "mmm" is the 3-character manufacturer ID, and +// "ccc" is the variable-length sentence type (it can be empty). +// +// No validation of manufacturer ID and talker ID is performed in this +// base class. For example, although "GP" is a common talker ID, it is not +// guaranteed to be transmitted by your particular device, and it IS NOT +// REQUIRED. If you need validation of these IDs, or you need to use the +// extra information provided by some devices, you have two independent +// options: +// +// 1. Enable SAVING the ID: When /decode/ returns DECODE_COMPLETED, the +// /talker_id/ and/or /mfr_id/ members will contain ID bytes. The entire +// sentence will be parsed, perhaps modifying members of /fix/. You should +// enable one or both IDs if you want the information in all sentences *and* +// you also want to know the ID bytes. This adds two bytes of RAM for the +// talker ID, and 3 bytes of RAM for the manufacturer ID. +// +// 2. Enable PARSING the ID: The virtual /parse_talker_id/ and +// /parse_mfr_id/ will receive each ID character as it is parsed. If it +// is not a valid ID, return /false/ to abort processing the rest of the +// sentence. No CPU time will be wasted on the invalid sentence, and no +// /fix/ members will be modified. You should enable this if you want to +// ignore some IDs. You must override /parse_talker_id/ and/or +// /parse_mfr_id/ in a derived class. +// + +//#define NMEAGPS_SAVE_TALKER_ID +//#define NMEAGPS_PARSE_TALKER_ID + +//#define NMEAGPS_PARSE_PROPRIETARY +#ifdef NMEAGPS_PARSE_PROPRIETARY + //#define NMEAGPS_SAVE_MFR_ID + #define NMEAGPS_PARSE_MFR_ID +#endif + +//------------------------------------------------------ +// Enable/disable tracking the current satellite array and, +// optionally, all the info for each satellite. +// + +//#define NMEAGPS_PARSE_SATELLITES +//#define NMEAGPS_PARSE_SATELLITE_INFO + +#ifdef NMEAGPS_PARSE_SATELLITES + #define NMEAGPS_MAX_SATELLITES (20) + + #ifndef GPS_FIX_SATELLITES + #error GPS_FIX_SATELLITES must be defined in GPSfix.h! + #endif + +#endif + +#if defined(NMEAGPS_PARSE_SATELLITE_INFO) & \ + !defined(NMEAGPS_PARSE_SATELLITES) + #error NMEAGPS_PARSE_SATELLITES must be defined! +#endif + +//------------------------------------------------------ +// Enable/disable gathering interface statistics: +// CRC errors and number of sentences received + +#define NMEAGPS_STATS + +//------------------------------------------------------ +// Configuration item for allowing derived types of NMEAGPS. +// If you derive classes from NMEAGPS, you *must* define NMEAGPS_DERIVED_TYPES. +// If not defined, virtuals are not used, with a slight size (2 bytes) and +// execution time savings. + +//#define NMEAGPS_DERIVED_TYPES + +#ifdef NMEAGPS_DERIVED_TYPES + #define NMEAGPS_VIRTUAL virtual +#else + #define NMEAGPS_VIRTUAL +#endif + +//----------------------------------- +// See if DERIVED_TYPES is required +#if (defined(NMEAGPS_PARSE_TALKER_ID) | defined(NMEAGPS_PARSE_MFR_ID)) & \ + !defined(NMEAGPS_DERIVED_TYPES) + #error You must define NMEAGPS_DERIVED_TYPES in NMEAGPS.h in order to parse Talker and/or Mfr IDs! +#endif + +//------------------------------------------------------ +// Becase the NMEA checksum is not very good at error detection, you can +// choose to enable additional validity checks. This trades a little more +// code and execution time for more reliability. +// +// Validation at the character level is a syntactic check only. For +// example, integer fields must contain characters in the range 0..9, +// latitude hemisphere letters can be 'N' or 'S'. Characters that are not +// valid for a particular field will cause the entire sentence to be +// rejected as an error, *regardless* of whether the checksum would pass. +#define NMEAGPS_VALIDATE_CHARS false + +// Validation at the field level is a semantic check. For +// example, latitude degrees must be in the range -90..+90. +// Values that are not valid for a particular field will cause the +// entire sentence to be rejected as an error, *regardless* of whether the +// checksum would pass. +#define NMEAGPS_VALIDATE_FIELDS false + +//------------------------------------------------------ +// Some devices may omit trailing commas at the end of some +// sentences. This may prevent the last field from being +// parsed correctly, because the parser for some types keep +// the value in an intermediate state until the complete +// field is received (e.g., parseDDDMM, parseFloat and +// parseZDA). +// +// Enabling this will inject a simulated comma when the end +// of a sentence is received and the last field parser +// indicated that it still needs one. + +#define NMEAGPS_COMMA_NEEDED + +//------------------------------------------------------ +// Some applications may want to recognize a sentence type +// without actually parsing any of the fields. Uncommenting +// this define will allow the nmeaMessage member to be set +// when *any* standard message is seen, even though that +// message is not enabled by a NMEAGPS_PARSE_xxx define above. +// No valid flags will be true for those sentences. + +#define NMEAGPS_RECOGNIZE_ALL + +//------------------------------------------------------ +// Sometimes, a little extra space is needed to parse an intermediate form. +// This config items enables extra space. + +//#define NMEAGPS_PARSING_SCRATCHPAD + +//------------------------------------------------------ +// If you need to know the exact UTC time at *any* time, +// not just after a fix arrives, you must calculate the +// offset between the Arduino micros() clock and the UTC +// time in a received fix. There are two ways to do this: +// +// 1) When the GPS quiet time ends and the new update interval begins. +// The timestamp will be set when the first character (the '$') of +// the new batch of sentences arrives from the GPS device. This is fairly +// accurate, but it will be delayed from the PPS edge by the GPS device's +// fix calculation time (usually ~100us). There is very little variance +// in this calculation time (usually < 30us), so all timestamps are +// delayed by a nearly-constant amount. +// +// NOTE: At update rates higher than 1Hz, the updates may arrive with +// some increasing variance. + +//#define NMEAGPS_TIMESTAMP_FROM_INTERVAL + +// 2) From the PPS pin of the GPS module. It is up to the application +// developer to decide how to capture that event. For example, you could: +// +// a) simply poll for it in loop and call UTCsecondStart(micros()); +// b) use attachInterrupt to call a Pin Change Interrupt ISR to save +// the micros() at the time of the interrupt (see NMEAGPS.h), or +// c) connect the PPS to an Input Capture pin. Set the +// associated TIMER frequency, calculate the elapsed time +// since the PPS edge, and add that to the current micros(). + +//#define NMEAGPS_TIMESTAMP_FROM_PPS + +#if defined( NMEAGPS_TIMESTAMP_FROM_INTERVAL ) & \ + defined( NMEAGPS_TIMESTAMP_FROM_PPS ) + #error You cannot enable both TIMESTAMP_FROM_INTERVAL and PPS in NMEAGPS_cfg.h! +#endif + +#endif \ No newline at end of file diff --git a/software/firmware/libraries/NeoGPS/src/NMEAGPSprivate.h b/software/firmware/libraries/NeoGPS/src/NMEAGPSprivate.h new file mode 100644 index 0000000..5f1ed6c --- /dev/null +++ b/software/firmware/libraries/NeoGPS/src/NMEAGPSprivate.h @@ -0,0 +1,408 @@ +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . + + protected: + //....................................................................... + // Table entry for NMEA sentence type string and its offset + // in enumerated nmea_msg_t. Proprietary sentences can be implemented + // in derived classes by adding a second table. Additional tables + // can be singly-linked through the /previous/ member. The instantiated + // class's table is the head, and should be returned by the derived + // /msg_table/ function. Tables should be sorted alphabetically. + + struct msg_table_t { + uint8_t offset; // nmea_msg_t enum starting value + const msg_table_t *previous; + uint8_t size; // number of entries in table array + const char * const *table; // array of NMEA sentence strings + }; + + static const msg_table_t nmea_msg_table __PROGMEM; + + NMEAGPS_VIRTUAL const msg_table_t *msg_table() const + { return &nmea_msg_table; }; + + //....................................................................... + // These virtual methods can accept or reject + // the talker ID (for standard sentences) or + // the manufacturer ID (for proprietary sentences). + // The default is to accept *all* IDs. + // Override them if you want to reject certain IDs, or you want + // to handle COMPLETED sentences from certain IDs differently. + + #ifdef NMEAGPS_PARSE_TALKER_ID + NMEAGPS_VIRTUAL bool parseTalkerID( char ) { return true; }; + #endif + + #ifdef NMEAGPS_PARSE_PROPRIETARY + #ifdef NMEAGPS_PARSE_MFR_ID + NMEAGPS_VIRTUAL bool parseMfrID( char ) { return true; }; + #endif + #endif + + public: + //....................................................................... + // Set all parsed data to initial values. + + void data_init() + { + fix().init(); + + #ifdef NMEAGPS_PARSE_SATELLITES + sat_count = 0; + #endif + } + + //....................................................................... + + enum merging_t { NO_MERGING, EXPLICIT_MERGING, IMPLICIT_MERGING }; + static const merging_t + merging = NMEAGPS_MERGING; // see NMEAGPS_cfg.h + + enum processing_style_t { PS_POLLING, PS_INTERRUPT }; + static const processing_style_t + processing_style = NMEAGPS_PROCESSING_STYLE; // see NMEAGPS_cfg.h + + static const bool keepNewestFixes = NMEAGPS_KEEP_NEWEST_FIXES; + + static const bool validateChars () { return NMEAGPS_VALIDATE_CHARS; } + static const bool validateFields() { return NMEAGPS_VALIDATE_FIELDS; } + + //....................................................................... + // Control access to this object. This preserves atomicity when + // the processing style is interrupt-driven. + + void lock() const + { + if (processing_style == PS_INTERRUPT) + noInterrupts(); + } + + void unlock() const + { + if (processing_style == PS_INTERRUPT) + interrupts(); + } + + protected: + //======================================================================= + // PARSING FINITE-STATE MACHINE + //======================================================================= + + // Current fix + gps_fix m_fix; + + // Current parser state + uint8_t crc; // accumulated CRC in the sentence + uint8_t fieldIndex; // index of current field in the sentence + uint8_t chrCount; // index of current character in current field + uint8_t decimal; // digits received after the decimal point + struct { + bool negative NEOGPS_BF(1); // field had a leading '-' + bool _comma_needed NEOGPS_BF(1); // field needs a comma to finish parsing + bool group_valid NEOGPS_BF(1); // multi-field group valid + bool _overrun NEOGPS_BF(1); // an entire fix was dropped + bool _intervalComplete NEOGPS_BF(1); // automatically set after LAST received + #if (NMEAGPS_FIX_MAX == 0) + bool _fixesAvailable NEOGPS_BF(1); + #endif + #ifdef NMEAGPS_PARSE_PROPRIETARY + bool proprietary NEOGPS_BF(1); // receiving proprietary message + #endif + } NEOGPS_PACKED; + + #ifdef NMEAGPS_PARSING_SCRATCHPAD + union { + uint32_t U4; + uint16_t U2[2]; + uint8_t U1[4]; + } scratchpad; + #endif + + bool comma_needed() + { + #ifdef NMEAGPS_COMMA_NEEDED + return _comma_needed; + #else + return false; + #endif + } + + void comma_needed( bool value ) + { + #ifdef NMEAGPS_COMMA_NEEDED + _comma_needed = value; + #endif + } + + // Internal FSM states + enum rxState_t { + NMEA_IDLE, // Waiting for initial '$' + NMEA_RECEIVING_HEADER, // Parsing sentence type field + NMEA_RECEIVING_DATA, // Parsing fields up to the terminating '*' + NMEA_RECEIVING_CRC // Receiving two-byte transmitted CRC + }; + CONST_CLASS_DATA uint8_t NMEA_FIRST_STATE = NMEA_IDLE; + CONST_CLASS_DATA uint8_t NMEA_LAST_STATE = NMEA_RECEIVING_CRC; + + rxState_t rxState NEOGPS_BF(8); + + //....................................................................... + + uint8_t _available() const volatile { return _fixesAvailable; }; + + //....................................................................... + // Buffered fixes. + + #if (NMEAGPS_FIX_MAX > 0) + gps_fix buffer[ NMEAGPS_FIX_MAX ]; // could be empty, see NMEAGPS_cfg.h + uint8_t _fixesAvailable; + uint8_t _firstFix; + uint8_t _currentFix; + #endif + + //....................................................................... + // Indicate that the next sentence should initialize the internal data. + // This is useful for coherency or custom filtering. + + bool intervalComplete() const { return _intervalComplete; } + void intervalComplete( bool val ) { _intervalComplete = val; } + + //....................................................................... + // Identify when an update interval is completed, according to the + // most recently-received sentence. In this base class, it just + // looks at the nmeaMessage member. Derived classes may have + // more complex, specific conditions. + + NMEAGPS_VIRTUAL bool intervalCompleted() const + { return (nmeaMessage == LAST_SENTENCE_IN_INTERVAL); } + // see NMEAGPS_cfg.h + + //....................................................................... + // When a fix has been fully assembled from a batch of sentences, as + // determined by the configured merging technique and ending with the + // LAST_SENTENCE_IN_INTERVAL, it is stored in the (optional) buffer + // of fixes. They are removed with /read()/. + + void storeFix(); + + //======================================================================= + // PARSING METHODS + //======================================================================= + + //....................................................................... + // Try to recognize an NMEA sentence type, after the IDs have been accepted. + + decode_t parseCommand( char c ); + decode_t parseCommand( const msg_table_t *msgs, uint8_t cmdCount, char c ); + + //....................................................................... + // Parse various NMEA sentences + + bool parseGGA( char chr ); + bool parseGLL( char chr ); + bool parseGSA( char chr ); + bool parseGST( char chr ); + bool parseGSV( char chr ); + bool parseRMC( char chr ); + bool parseVTG( char chr ); + bool parseZDA( char chr ); + + //....................................................................... + // Depending on the NMEA sentence type, parse one field of an expected type. + + NMEAGPS_VIRTUAL bool parseField( char chr ); + + //....................................................................... + // Parse the primary NMEA field types into /fix/ members. + + bool parseFix ( char chr ); // aka STATUS or MODE + bool parseTime ( char chr ); + bool parseDDMMYY ( char chr ); + bool parseLat ( char chr ); + bool parseNS ( char chr ); + bool parseLon ( char chr ); + bool parseEW ( char chr ); + bool parseSpeed ( char chr ); + bool parseHeading ( char chr ); + bool parseAlt ( char chr ); + bool parseGeoidHeight( char chr ); + bool parseHDOP ( char chr ); + bool parseVDOP ( char chr ); + bool parsePDOP ( char chr ); + bool parse_lat_err ( char chr ); + bool parse_lon_err ( char chr ); + bool parse_alt_err ( char chr ); + bool parseSatellites ( char chr ); + + // Helper macro for parsing the 4 consecutive fields of a location + #define PARSE_LOC(i) case i: return parseLat( chr );\ + case i+1: return parseNS ( chr ); \ + case i+2: return parseLon( chr ); \ + case i+3: return parseEW ( chr ); + + //....................................................................... + // Parse floating-point numbers into a /whole_frac/ + // @return true when the value is fully populated. + + bool parseFloat( gps_fix::whole_frac & val, char chr, uint8_t max_decimal ); + + //....................................................................... + // Parse floating-point numbers into a uint16_t + // @return true when the value is fully populated. + + bool parseFloat( uint16_t & val, char chr, uint8_t max_decimal ); + + //....................................................................... + // Parse NMEA lat/lon dddmm.mmmm degrees + + bool parseDDDMM + ( + #if defined( GPS_FIX_LOCATION ) + int32_t & val, + #endif + #if defined( GPS_FIX_LOCATION_DMS ) + DMS_t & dms, + #endif + char chr + ); + + //....................................................................... + // Parse integer into 8-bit int + // @return true when non-empty value + + bool parseInt( uint8_t &val, uint8_t chr ) + { + negative = false; + bool is_comma = (chr == ','); + + if (chrCount == 0) { + if (is_comma) + return false; // empty field! + + if (((validateChars() || validateFields()) && (chr == '-')) || + (validateChars() && !isdigit( chr ))) + sentenceInvalid(); + else + val = (chr - '0'); + + } else if (!is_comma) { + + if (validateChars() && !isdigit( chr )) + sentenceInvalid(); + else + val = (val*10) + (chr - '0'); + } + return true; + } + + //....................................................................... + // Parse integer into signed 8-bit int + // @return true when non-empty value + + bool parseInt( int8_t &val, uint8_t chr ) + { + bool is_comma = (chr == ','); + + if (chrCount == 0) { + if (is_comma) + return false; // empty field! + + negative = (chr == '-'); + if (negative) { + comma_needed( true ); // to negate + val = 0; + } else if (validateChars() && !isdigit( chr )) { + sentenceInvalid(); + } else { + val = (chr - '0'); + } + } else if (!is_comma) { + val = (val*10) + (chr - '0'); + + } else if (negative) { + val = -val; + } + + return true; + } + + //....................................................................... + // Parse integer into 16-bit int + // @return true when non-empty value + + bool parseInt( uint16_t &val, uint8_t chr ) + { + negative = false; + + bool is_comma = (chr == ','); + if (chrCount == 0) { + if (is_comma) + return false; // empty field! + + if (((validateChars() || validateFields()) && (chr == '-')) || + (validateChars() && !isdigit( chr ))) + sentenceInvalid(); + else + val = (chr - '0'); + + } else if (!is_comma) { + + if (validateChars() && !isdigit( chr )) + sentenceInvalid(); + else + val = (val*10) + (chr - '0'); + } + return true; + } + + //....................................................................... + // Parse integer into 32-bit int + // @return true when non-empty value + + bool parseInt( uint32_t &val, uint8_t chr ) + { + negative = false; + + bool is_comma = (chr == ','); + if (chrCount == 0) { + if (is_comma) + return false; // empty field! + + if (((validateChars() || validateFields()) && (chr == '-')) || + (validateChars() && !isdigit( chr ))) + sentenceInvalid(); + else + val = (chr - '0'); + + } else if (!is_comma) { + + if (validateChars() && !isdigit( chr )) + sentenceInvalid(); + else + val = (val*10) + (chr - '0'); + } + return true; + } + + private: + void sentenceBegin (); + void sentenceOk (); + void sentenceInvalid (); + void sentenceUnrecognized(); + void headerReceived (); + diff --git a/software/firmware/libraries/NeoGPS/src/NeoGPS_cfg.h b/software/firmware/libraries/NeoGPS/src/NeoGPS_cfg.h new file mode 100644 index 0000000..39525b0 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/src/NeoGPS_cfg.h @@ -0,0 +1,111 @@ +#ifndef NEOGPS_CFG +#define NEOGPS_CFG + +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . + +//------------------------------------------------------------------------ +// Enable/disable packed data structures. +// +// Enabling packed data structures will use two less-portable language +// features of GCC to reduce RAM requirements. Although it was expected to slightly increase execution time and code size, the reverse is true on 8-bit AVRs: the code is smaller and faster with packing enabled. +// +// Disabling packed data structures will be very portable to other +// platforms. NeoGPS configurations will use slightly more RAM, and on +// 8-bit AVRs, the speed is slightly slower, and the code is slightly +// larger. There may be no choice but to disable packing on processors +// that do not support packed structures. +// +// There may also be compiler-specific switches that affect packing and the +// code which accesses packed members. YMMV. + +#ifdef __AVR__ + #define NEOGPS_PACKED_DATA +#endif + +//------------------------------------------------------------------------ +// Based on the above define, choose which set of packing macros should +// be used in the rest of the NeoGPS package. Do not change these defines. + +#ifdef NEOGPS_PACKED_DATA + + // This is for specifying the number of bits to be used for a + // member of a struct. Booleans are typically one bit. + #define NEOGPS_BF(b) :b + + // This is for requesting the compiler to pack the struct or class members + // "as closely as possible". This is a compiler-dependent interpretation. + #define NEOGPS_PACKED __attribute__((packed)) + +#else + + // Let the compiler do whatever it wants. + + #define NEOGPS_PACKED + #define NEOGPS_BF(b) + +#endif + +//------------------------------------------------------------------------ +// Accommodate C++ compiler and IDE changes. +// +// Declaring constants as class data instead of instance data helps avoid +// collisions with #define names, and allows the compiler to perform more +// checks on their usage. +// +// Until C++ 10 and IDE 1.6.8, initialized class data constants +// were declared like this: +// +// static const = ; +// +// Now, non-simple types (e.g., float) must be declared as +// +// static constexpr = ; +// +// The good news is that this allows the compiler to optimize out an +// expression that is "promised" to be "evaluatable" as a constant. +// The bad news is that it introduces a new language keyword, and the old +// code raises an error. +// +// TODO: Evaluate the requirement for the "static" keyword. +// TODO: Evaluate using a C++ version preprocessor symbol for the #if. +// +// The CONST_CLASS_DATA define will expand to the appropriate keywords. +// + +#if (ARDUINO < 10606) | ((10700 <= ARDUINO) & (ARDUINO <= 10799)) | ((107000 <= ARDUINO) & (ARDUINO <= 107999)) + + #define CONST_CLASS_DATA static const + +#else + + #define CONST_CLASS_DATA static constexpr + +#endif + +//------------------------------------------------------------------------ +// The PROGMEM definitions are not correct for Zero, MKR1000 and +// earlier versions of Teensy boards + +#if defined(ARDUINO_SAMD_MKRZERO) | defined(ARDUINO_SAMD_ZERO) | \ + (defined(TEENSYDUINO) && (TEENSYDUINO < 139)) + #undef pgm_read_ptr + #define pgm_read_ptr(addr) (*(const void **)(addr)) +#endif + + +#endif diff --git a/software/firmware/libraries/NeoGPS/src/NeoTime.cpp b/software/firmware/libraries/NeoGPS/src/NeoTime.cpp new file mode 100644 index 0000000..92adc8a --- /dev/null +++ b/software/firmware/libraries/NeoGPS/src/NeoTime.cpp @@ -0,0 +1,208 @@ +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . + +#include "NeoTime.h" + +// For strtoul declaration +#include + +#include + +Print & operator<<( Print& outs, const NeoGPS::time_t& t ) +{ + outs.print( t.full_year( t.year ) ); + outs.write( '-' ); + if (t.month < 10) outs.write( '0' ); + outs.print( t.month ); + outs.write( '-' ); + if (t.date < 10) outs.write( '0' ); + outs.print( t.date ); + outs.write( ' ' ); + if (t.hours < 10) outs.write( '0' ); + outs.print( t.hours ); + outs.write( ':' ); + if (t.minutes < 10) outs.write( '0' ); + outs.print( t.minutes ); + outs.write( ':' ); + if (t.seconds < 10) outs.write( '0' ); + outs.print( t.seconds ); + + return outs; +} + +using NeoGPS::time_t; + +bool time_t::parse(str_P s) +{ + static size_t BUF_MAX = 32; + char buf[BUF_MAX]; + strcpy_P(buf, s); + char* sp = &buf[0]; + uint16_t value = strtoul(sp, &sp, 10); + + if (*sp != '-') return false; + year = value % 100; + if (full_year() != value) return false; + + value = strtoul(sp + 1, &sp, 10); + if (*sp != '-') return false; + month = value; + + value = strtoul(sp + 1, &sp, 10); + if (*sp != ' ') return false; + date = value; + + value = strtoul(sp + 1, &sp, 10); + if (*sp != ':') return false; + hours = value; + + value = strtoul(sp + 1, &sp, 10); + if (*sp != ':') return false; + minutes = value; + + value = strtoul(sp + 1, &sp, 10); + if (*sp != 0) return false; + seconds = value; + + return (is_valid()); +} + +#ifdef TIME_EPOCH_MODIFIABLE + uint16_t time_t::s_epoch_year = Y2K_EPOCH_YEAR; + uint8_t time_t::s_epoch_offset = 0; + uint8_t time_t::s_epoch_weekday = Y2K_EPOCH_WEEKDAY; + uint8_t time_t::s_pivot_year = 0; +#endif + +const uint8_t time_t::days_in[] __PROGMEM = { + 0, 31, 28, 31, 30, 31, 30, 31, 31, 30, 31, 30, 31 +}; + +time_t::time_t(clock_t c) +{ + uint16_t dayno = c / SECONDS_PER_DAY; + c -= dayno * (uint32_t) SECONDS_PER_DAY; + day = weekday_for(dayno); + + uint16_t y = epoch_year(); + for (;;) { + uint16_t days = days_per( y ); + if (dayno < days) break; + dayno -= days; + y++; + } + bool leap_year = is_leap(y); + y -= epoch_year(); + y += epoch_offset(); + while (y > 100) + y -= 100; + year = y; + + month = 1; + for (;;) { + uint8_t days = pgm_read_byte(&days_in[month]); + if (leap_year && (month == 2)) days++; + if (dayno < days) break; + dayno -= days; + month++; + } + date = dayno + 1; + + hours = c / SECONDS_PER_HOUR; + + uint16_t c_ms; + if (hours < 18) // save 16uS + c_ms = (uint16_t) c - (hours * (uint16_t) SECONDS_PER_HOUR); + else + c_ms = c - (hours * (uint32_t) SECONDS_PER_HOUR); + minutes = c_ms / SECONDS_PER_MINUTE; + seconds = c_ms - (minutes * SECONDS_PER_MINUTE); +} + +void time_t::init() +{ + seconds = + hours = + minutes = 0; + date = 1; + month = 1; + year = epoch_year() % 100; + day = epoch_weekday(); +} + +time_t::operator clock_t() const +{ + clock_t c = days() * SECONDS_PER_DAY; + if (hours < 18) + c += hours * (uint16_t) SECONDS_PER_HOUR; + else + c += hours * (uint32_t) SECONDS_PER_HOUR; + c += minutes * (uint16_t) SECONDS_PER_MINUTE; + c += seconds; + + return (c); +} + +uint16_t time_t::days() const +{ + uint16_t day_count = day_of_year(); + + uint16_t y = full_year(); + while (y-- > epoch_year()) + day_count += days_per(y); + + return (day_count); +} + +uint16_t time_t::day_of_year() const +{ + uint16_t dayno = date - 1; + bool leap_year = is_leap(); + + for (uint8_t m = 1; m < month; m++) { + dayno += pgm_read_byte(&days_in[m]); + if (leap_year && (m == 2)) dayno++; + } + + return (dayno); +} + +#ifdef TIME_EPOCH_MODIFIABLE + void time_t::use_fastest_epoch() + { + // Figure out when we were compiled and use the year for a really + // fast epoch_year. Format "MMM DD YYYY" + const char* compile_date = (const char *) PSTR(__DATE__); + uint16_t compile_year = 0; + for (uint8_t i = 7; i < 11; i++) + compile_year = compile_year*10 + (pgm_read_byte(&compile_date[i]) - '0'); + + // Temporarily set a Y2K epoch so we can figure out the day for + // January 1 of this year + epoch_year ( Y2K_EPOCH_YEAR ); + epoch_weekday ( Y2K_EPOCH_WEEKDAY ); + + time_t this_year(0); + this_year.year = compile_year % 100; + this_year.set_day(); + uint8_t compile_weekday = this_year.day; + + epoch_year ( compile_year ); + epoch_weekday( compile_weekday ); + pivot_year ( this_year.year ); + } +#endif \ No newline at end of file diff --git a/software/firmware/libraries/NeoGPS/src/NeoTime.h b/software/firmware/libraries/NeoGPS/src/NeoTime.h new file mode 100644 index 0000000..6c3564e --- /dev/null +++ b/software/firmware/libraries/NeoGPS/src/NeoTime.h @@ -0,0 +1,307 @@ +#ifndef TIME_H +#define TIME_H + +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . + +#include + +#include "NeoGPS_cfg.h" +#include "CosaCompat.h" + +namespace NeoGPS { + +//------------------------------------------------------ +// Enable/disable run-time modification of the epoch. +// If this is defined, epoch mutators are available. +// If this is not defined, the epoch is a hard-coded constant. +// Only epoch accessors are available. +//#define TIME_EPOCH_MODIFIABLE + +/** + * Number of seconds elapsed since January 1 of the Epoch Year, + * 00:00:00 +0000 (UTC). + */ +typedef uint32_t clock_t; + +const uint8_t SECONDS_PER_MINUTE = 60; +const uint8_t MINUTES_PER_HOUR = 60; +const uint16_t SECONDS_PER_HOUR = (uint16_t) SECONDS_PER_MINUTE * MINUTES_PER_HOUR; +const uint8_t HOURS_PER_DAY = 24; +const uint32_t SECONDS_PER_DAY = (uint32_t) SECONDS_PER_HOUR * HOURS_PER_DAY; +const uint8_t DAYS_PER_WEEK = 7; + +/** + * Common date/time structure + */ +struct time_t { + + enum weekday_t { + SUNDAY = 1, + MONDAY = 2, + TUESDAY = 3, + WEDNESDAY = 4, + THURSDAY = 5, + FRIDAY = 6, + SATURDAY = 7 + }; + + // NTP epoch year and weekday (Monday) + static const uint16_t NTP_EPOCH_YEAR = 1900; + static const uint8_t NTP_EPOCH_WEEKDAY = MONDAY; + + // POSIX epoch year and weekday (Thursday) + static const uint16_t POSIX_EPOCH_YEAR = 1970; + static const uint8_t POSIX_EPOCH_WEEKDAY = THURSDAY; + + // Y2K epoch year and weekday (Saturday) + static const uint16_t Y2K_EPOCH_YEAR = 2000; + static const uint8_t Y2K_EPOCH_WEEKDAY = SATURDAY; + + uint8_t seconds; //!< 00-59 + uint8_t minutes; //!< 00-59 + uint8_t hours; //!< 00-23 + uint8_t day; //!< 01-07 Day of Week + uint8_t date; //!< 01-31 Day of Month + uint8_t month; //!< 01-12 + uint8_t year; //!< 00-99 + + /** + * Constructor. + */ + time_t() {} + + /** + * Construct from seconds since the Epoch. + * @param[in] c clock. + */ + time_t(clock_t c); + + /** + * Initialize to January 1 of the Epoch Year, 00:00:00 + */ + void init(); + + /** + * Convert to seconds. + * @return seconds from epoch. + */ + operator clock_t() const; + + /** + * Offset by a number of seconds. + * @param[in] offset in seconds. + */ + void operator +=( clock_t offset ) + { *this = offset + operator clock_t(); } + + /** + * Set day member from current value. This is a relatively expensive + * operation, so the weekday is only calculated when requested. + */ + void set_day() + { + day = weekday_for(days()); + } + + /** + * Convert to days. + * @return days from January 1 of the epoch year. + */ + uint16_t days() const; + + /** + * Calculate day of the current year. + * @return days from January 1, which is day zero. + */ + uint16_t day_of_year() const; + + /** + * Calculate 4-digit year from internal 2-digit year member. + * @return 4-digit year. + */ + uint16_t full_year() const + { + return full_year(year); + } + + /** + * Calculate 4-digit year from a 2-digit year + * @param[in] year (4-digit). + * @return true if /year/ is a leap year. + */ + static uint16_t full_year( uint8_t year ) + { + uint16_t y = year; + + if (y < pivot_year()) + y += 100 * (epoch_year()/100 + 1); + else + y += 100 * (epoch_year()/100); + + return y; + } + + /** + * Determine whether the current year is a leap year. + * @returns true if the two-digit /year/ member is a leap year. + */ + bool is_leap() const + { + return is_leap(full_year()); + } + + /** + * Determine whether the 4-digit /year/ is a leap year. + * @param[in] year (4-digit). + * @return true if /year/ is a leap year. + */ + static bool is_leap(uint16_t year) + { + if (year % 4) return false; + uint16_t y = year % 400; + return (y == 0) || ((y != 100) && (y != 200) && (y != 300)); + } + + /** + * Calculate how many days are in the specified year. + * @param[in] year (4-digit). + * @return number of days. + */ + static uint16_t days_per(uint16_t year) + { + return (365 + is_leap(year)); + } + + /** + * Determine the day of the week for the specified day number + * @param[in] dayno number as counted from January 1 of the epoch year. + * @return weekday number 1..7, as for the /day/ member. + */ + static uint8_t weekday_for(uint16_t dayno) + { + return ((dayno+epoch_weekday()-1) % DAYS_PER_WEEK) + 1; + } + + /** + * Check that all members, EXCEPT FOR day, are set to a coherent date/time. + * @return true if valid date/time. + */ + bool is_valid() const + { + return + ((year <= 99) && + (1 <= month) && (month <= 12) && + ((1 <= date) && + ((date <= pgm_read_byte(&days_in[month])) || + ((month == 2) && is_leap() && (date == 29)))) && + (hours <= 23) && + (minutes <= 59) && + (seconds <= 59)); + } + + /** + * Set the epoch year for all time_t operations. Note that the pivot + * year defaults to the epoch_year % 100. Valid years will be in the + * range epoch_year..epoch_year+99. Selecting a different pivot year + * will slide this range to the right. + * @param[in] y epoch year to set. + * See also /full_year/. + */ + #ifdef TIME_EPOCH_MODIFIABLE + static void epoch_year(uint16_t y) + { + s_epoch_year = y; + epoch_offset( s_epoch_year % 100 ); + pivot_year( epoch_offset() ); + } + #endif + + /** + * Get the epoch year. + * @return year. + */ + static uint16_t epoch_year() + { + return (s_epoch_year); + } + + static uint8_t epoch_weekday() { return s_epoch_weekday; }; +#ifdef TIME_EPOCH_MODIFIABLE + static void epoch_weekday( uint8_t ew ) { s_epoch_weekday = ew; }; +#endif + + /** + * The pivot year determine the range of years WRT the epoch_year + * For example, an epoch year of 2000 and a pivot year of 80 will + * allow years in the range 1980 to 2079. Default 0 for Y2K_EPOCH. + */ + static uint8_t pivot_year() { return s_pivot_year; }; + #ifdef TIME_EPOCH_MODIFIABLE + static void pivot_year( uint8_t py ) { s_pivot_year = py; }; + #endif + + #ifdef TIME_EPOCH_MODIFIABLE + /** + * Use the current year for the epoch year. This will result in the + * best performance of conversions, but dates/times before January 1 + * of the epoch year cannot be represented. + */ + static void use_fastest_epoch(); + #endif + + /** + * Parse a character string and fill out members. + * @param[in] s PROGMEM character string with format "YYYY-MM-DD HH:MM:SS". + * @return success. + */ + bool parse(str_P s); + + static const uint8_t days_in[] PROGMEM; // month index is 1..12, PROGMEM + +protected: + static uint8_t epoch_offset() { return s_epoch_offset; }; + + #ifdef TIME_EPOCH_MODIFIABLE + static void epoch_offset( uint8_t eo ) { s_epoch_offset = eo; }; + + static uint16_t s_epoch_year; + static uint8_t s_pivot_year; + static uint8_t s_epoch_offset; + static uint8_t s_epoch_weekday; + #else + static const uint16_t s_epoch_year = Y2K_EPOCH_YEAR; + static const uint8_t s_pivot_year = s_epoch_year % 100; + static const uint8_t s_epoch_offset = s_pivot_year; + static const uint8_t s_epoch_weekday = Y2K_EPOCH_WEEKDAY; + #endif + +} NEOGPS_PACKED; + +}; // namespace NeoGPS + +class Print; + +/** + * Print the date/time to the given stream with the format "YYYY-MM-DD HH:MM:SS". + * @param[in] outs output stream. + * @param[in] t time structure. + * @return iostream. + */ +Print & operator <<( Print & outs, const NeoGPS::time_t &t ); + +#endif diff --git a/software/firmware/libraries/NeoGPS/src/Streamers.cpp b/software/firmware/libraries/NeoGPS/src/Streamers.cpp new file mode 100644 index 0000000..1c2ab04 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/src/Streamers.cpp @@ -0,0 +1,421 @@ +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . + +#include "Streamers.h" +#include "NMEAGPS.h" + +//#define USE_FLOAT + +Print& operator <<( Print &outs, const bool b ) + { outs.print( b ? 't' : 'f' ); return outs; } + +Print& operator <<( Print &outs, const char c ) { outs.print(c); return outs; } + +Print& operator <<( Print &outs, const uint16_t v ) { outs.print(v); return outs; } + +Print& operator <<( Print &outs, const uint32_t v ) { outs.print(v); return outs; } + +Print& operator <<( Print &outs, const int32_t v ) { outs.print(v); return outs; } + +Print& operator <<( Print &outs, const uint8_t v ) { outs.print(v); return outs; } + +Print& operator <<( Print &outs, const __FlashStringHelper *s ) +{ outs.print(s); return outs; } + +//------------------------------------------ + +const char gps_fix_header[] __PROGMEM = + "Status," + + #if defined(GPS_FIX_DATE) | defined(GPS_FIX_TIME) + + "UTC " + + #if defined(GPS_FIX_DATE) + "Date" + #endif + #if defined(GPS_FIX_DATE) & defined(GPS_FIX_TIME) + "/" + #endif + #if defined(GPS_FIX_TIME) + "Time" + #endif + + #else + "s" + #endif + + "," + + #ifdef GPS_FIX_LOCATION + "Lat,Lon," + #endif + + #ifdef GPS_FIX_LOCATION_DMS + "DMS," + #endif + + #if defined(GPS_FIX_HEADING) + "Hdg," + #endif + + #if defined(GPS_FIX_SPEED) + "Spd," + #endif + + #if defined(GPS_FIX_ALTITUDE) + "Alt," + #endif + + #if defined(GPS_FIX_HDOP) + "HDOP," + #endif + + #if defined(GPS_FIX_VDOP) + "VDOP," + #endif + + #if defined(GPS_FIX_PDOP) + "PDOP," + #endif + + #if defined(GPS_FIX_LAT_ERR) + "Lat err," + #endif + + #if defined(GPS_FIX_LON_ERR) + "Lon err," + #endif + + #if defined(GPS_FIX_ALT_ERR) + "Alt err," + #endif + + #if defined(GPS_FIX_GEOID_HEIGHT) + "Geoid Ht," + #endif + + #if defined(GPS_FIX_SATELLITES) + "Sats," + #endif + + ; + +//............... + +#ifdef GPS_FIX_LOCATION_DMS + + static void printDMS( Print & outs, const DMS_t & dms ) + { + if (dms.degrees < 10) + outs.write( '0' ); + outs.print( dms.degrees ); + outs.write( ' ' ); + + if (dms.minutes < 10) + outs.write( '0' ); + outs.print( dms.minutes ); + outs.print( F("\' ") ); + + if (dms.seconds_whole < 10) + outs.write( '0' ); + outs.print( dms.seconds_whole ); + outs.write( '.' ); + + if (dms.seconds_frac < 100) + outs.write( '0' ); + if (dms.seconds_frac < 10) + outs.write( '0' ); + outs.print( dms.seconds_frac ); + outs.print( F("\" ") ); + + } // printDMS + +#endif +//............... + +Print & operator <<( Print &outs, const gps_fix &fix ) +{ + if (fix.valid.status) + outs << (uint8_t) fix.status; + outs << ','; + + #if defined(GPS_FIX_DATE) | defined(GPS_FIX_TIME) + bool someTime = false; + + #if defined(GPS_FIX_DATE) + someTime |= fix.valid.date; + #endif + + #if defined(GPS_FIX_TIME) + someTime |= fix.valid.time; + #endif + + if (someTime) { + outs << fix.dateTime << '.'; + uint16_t ms = fix.dateTime_ms(); + if (ms < 100) + outs << '0'; + if (ms < 10) + outs << '0'; + outs << ms; + } + outs << ','; + + #else + + // Date/Time not enabled, just output the interval number + static uint32_t sequence = 0L; + outs << sequence++ << ','; + + #endif + + #ifdef USE_FLOAT + #ifdef GPS_FIX_LOCATION + if (fix.valid.location) { + outs.print( fix.latitude(), 6 ); + outs << ','; + outs.print( fix.longitude(), 6 ); + } else + outs << ','; + outs << ','; + #endif + #ifdef GPS_FIX_LOCATION_DMS + if (fix.valid.location) { + printDMS( outs, fix.latitudeDMS ); + outs.print( fix.latitudeDMS.NS() ); + outs.write( ' ' ); + if (fix.longitudeDMS.degrees < 100) + outs.write( '0' ); + printDMS( outs, fix.longitudeDMS ); + outs.print( fix.longitudeDMS.EW() ); + } + outs << ','; + #endif + #ifdef GPS_FIX_HEADING + if (fix.valid.heading) + outs.print( fix.heading(), 2 ); + outs << ','; + #endif + #ifdef GPS_FIX_SPEED + if (fix.valid.speed) + outs.print( fix.speed(), 3 ); // knots + outs << ','; + #endif + #ifdef GPS_FIX_ALTITUDE + if (fix.valid.altitude) + outs.print( fix.altitude(), 2 ); + outs << ','; + #endif + + #ifdef GPS_FIX_HDOP + if (fix.valid.hdop) + outs.print( (fix.hdop * 0.001), 3 ); + outs << ','; + #endif + #ifdef GPS_FIX_VDOP + if (fix.valid.vdop) + outs.print( (fix.vdop * 0.001), 3 ); + outs << ','; + #endif + #ifdef GPS_FIX_PDOP + if (fix.valid.pdop) + outs.print( (fix.pdop * 0.001), 3 ); + outs << ','; + #endif + + #ifdef GPS_FIX_LAT_ERR + if (fix.valid.lat_err) + outs.print( fix.lat_err(), 2 ); + outs << ','; + #endif + #ifdef GPS_FIX_LON_ERR + if (fix.valid.lon_err) + outs.print( fix.lon_err(), 2 ); + outs << ','; + #endif + #ifdef GPS_FIX_ALT_ERR + if (fix.valid.alt_err) + outs.print( fix.alt_err(), 2 ); + outs << ','; + #endif + + #ifdef GPS_FIX_GEOID_HEIGHT + if (fix.valid.geoidHeight) + outs.print( fix.geoidHeight(), 2 ); + outs << ','; + #endif + + #else + + // not USE_FLOAT ---------------------- + + #ifdef GPS_FIX_LOCATION + if (fix.valid.location) + outs << fix.latitudeL() << ',' << fix.longitudeL(); + else + outs << ','; + outs << ','; + #endif + #ifdef GPS_FIX_LOCATION_DMS + if (fix.valid.location) { + printDMS( outs, fix.latitudeDMS ); + outs.print( fix.latitudeDMS.NS() ); + outs.write( ' ' ); + if (fix.longitudeDMS.degrees < 100) + outs.write( '0' ); + printDMS( outs, fix.longitudeDMS ); + outs.print( fix.longitudeDMS.EW() ); + } + outs << ','; + #endif + #ifdef GPS_FIX_HEADING + if (fix.valid.heading) + outs << fix.heading_cd(); + outs << ','; + #endif + #ifdef GPS_FIX_SPEED + if (fix.valid.speed) + outs << fix.speed_mkn(); + outs << ','; + #endif + #ifdef GPS_FIX_ALTITUDE + if (fix.valid.altitude) + outs << fix.altitude_cm(); + outs << ','; + #endif + + #ifdef GPS_FIX_HDOP + if (fix.valid.hdop) + outs << fix.hdop; + outs << ','; + #endif + #ifdef GPS_FIX_VDOP + if (fix.valid.vdop) + outs << fix.vdop; + outs << ','; + #endif + #ifdef GPS_FIX_PDOP + if (fix.valid.pdop) + outs << fix.pdop; + outs << ','; + #endif + + #ifdef GPS_FIX_LAT_ERR + if (fix.valid.lat_err) + outs << fix.lat_err_cm; + outs << ','; + #endif + #ifdef GPS_FIX_LON_ERR + if (fix.valid.lon_err) + outs << fix.lon_err_cm; + outs << ','; + #endif + #ifdef GPS_FIX_ALT_ERR + if (fix.valid.alt_err) + outs << fix.alt_err_cm; + outs << ','; + #endif + + #ifdef GPS_FIX_GEOID_HEIGHT + if (fix.valid.geoidHeight) + outs << fix.geoidHeight_cm(); + outs << ','; + #endif + + #endif + + #ifdef GPS_FIX_SATELLITES + if (fix.valid.satellites) + outs << fix.satellites; + outs << ','; + #endif + + return outs; +} + +//----------------------------- + +static const char NMEAGPS_header[] __PROGMEM = + #if defined(NMEAGPS_TIMESTAMP_FROM_INTERVAL) | defined(NMEAGPS_TIMESTAMP_FROM_PPS) + "micros()," + #endif + + #if defined(NMEAGPS_PARSE_SATELLITES) + "[sat" + #if defined(NMEAGPS_PARSE_SATELLITE_INFO) + " elev/az @ SNR" + #endif + "]," + #endif + + #ifdef NMEAGPS_STATS + "Rx ok,Rx err,Rx chars," + #endif + + ""; + +void trace_header( Print & outs ) +{ + outs.print( (const __FlashStringHelper *) &gps_fix_header[0] ); + outs.print( (const __FlashStringHelper *) &NMEAGPS_header[0] ); + + outs << '\n'; +} + +//-------------------------- + +void trace_all( Print & outs, const NMEAGPS &gps, const gps_fix &fix ) +{ + outs << fix; + + #if defined(NMEAGPS_TIMESTAMP_FROM_INTERVAL) | defined(NMEAGPS_TIMESTAMP_FROM_PPS) + outs << gps.UTCsecondStart(); + outs << ','; + #endif + + #if defined(NMEAGPS_PARSE_SATELLITES) + outs << '['; + + for (uint8_t i=0; i < gps.sat_count; i++) { + outs << gps.satellites[i].id; + + #if defined(NMEAGPS_PARSE_SATELLITE_INFO) + outs << ' ' << + gps.satellites[i].elevation << '/' << gps.satellites[i].azimuth; + outs << '@'; + if (gps.satellites[i].tracked) + outs << gps.satellites[i].snr; + else + outs << '-'; + #endif + + outs << ','; + } + + outs << F("],"); + #endif + + #ifdef NMEAGPS_STATS + outs << gps.statistics.ok << ',' + << gps.statistics.errors << ',' + << gps.statistics.chars << ','; + #endif + + outs << '\n'; + +} // trace_all diff --git a/software/firmware/libraries/NeoGPS/src/Streamers.h b/software/firmware/libraries/NeoGPS/src/Streamers.h new file mode 100644 index 0000000..f942931 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/src/Streamers.h @@ -0,0 +1,50 @@ +#ifndef STREAMERS_H +#define STREAMERS_H + +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . + +#include + +extern Print & operator <<( Print & outs, const bool b ); +extern Print & operator <<( Print & outs, const char c ); +extern Print & operator <<( Print & outs, const uint16_t v ); +extern Print & operator <<( Print & outs, const uint32_t v ); +extern Print & operator <<( Print & outs, const int32_t v ); +extern Print & operator <<( Print & outs, const uint8_t v ); +extern Print & operator <<( Print & outs, const __FlashStringHelper *s ); + +class gps_fix; + +/** + * Print valid fix data to the given stream with the format + * "status,dateTime,lat,lon,heading,speed,altitude,satellites, + * hdop,vdop,pdop,lat_err,lon_err,alt_err" + * The "header" above contains the actual compile-time configuration. + * A comma-separated field will be empty if the data is NOT valid. + * @param[in] outs output stream. + * @param[in] fix gps_fix instance. + * @return iostream. + */ +extern Print & operator <<( Print &outs, const gps_fix &fix ); + +class NMEAGPS; + +extern void trace_header( Print & outs ); +extern void trace_all( Print & outs, const NMEAGPS &gps, const gps_fix &fix ); + +#endif \ No newline at end of file diff --git a/software/firmware/libraries/NeoGPS/src/ublox/ubxGPS.cpp b/software/firmware/libraries/NeoGPS/src/ublox/ubxGPS.cpp new file mode 100644 index 0000000..f857ba8 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/src/ublox/ubxGPS.cpp @@ -0,0 +1,1204 @@ +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . + +#include "NMEAGPS_cfg.h" +// Disable the entire file if derived types are not allowed. +#ifdef NMEAGPS_DERIVED_TYPES + +#include "ublox/ubxGPS.h" + +// Check configurations + +#if defined( UBLOX_PARSE_POSLLH ) & \ + ( defined( GPS_FIX_LAT_ERR ) | \ + defined( GPS_FIX_LON_ERR ) | \ + defined( GPS_FIX_ALT_ERR ) ) & \ + !defined( NMEAGPS_PARSING_SCRATCHPAD ) + + // The NAV_POSLLH message has 4-byte received errors in mm. + // These must be converted to the 2-byte gps_fix errors in cm. + // There's no easy way to perform this conversion as the bytes are + // being received, especially when the LSB is received first. + #error You must enable NMEAGPS_PARSING_SCRATCHPAD in NMEAGPS_cfg.h + +#endif + +using namespace ublox; + +//---------------------------------- + +void ubloxGPS::rxBegin() +{ + if (intervalComplete()) { + // GPS quiet time is over, this is the start of a new interval. + + #if defined(NMEAGPS_TIMESTAMP_FROM_INTERVAL) & \ + ( defined(GPS_FIX_DATE) | defined(GPS_FIX_TIME) ) + _IntervalStart = micros(); + #endif + + intervalComplete( false ); + } + + m_rx_msg.init(); + storage = (msg_t *) NULL; + chrCount = 0; + nmeaMessage = (nmea_msg_t) UBX_MSG; +} + +bool ubloxGPS::rxEnd() +{ + bool visible_msg = false; + + if (rx().msg_class == UBX_ACK) { + + if (ack_expected && ack_same_as_sent) { + if (rx().msg_id == UBX_ACK_ACK) + ack_received = true; + else if (rx().msg_id == UBX_ACK_NAK) + nak_received = true; + ack_expected = false; + } + + } else if (rx().msg_class != UBX_UNK) { + + #ifdef NMEAGPS_STATS + statistics.ok++; + #endif + + visible_msg = true; +//if (!visible_msg) trace << F("XXX"); + + if (storage) { + if (reply_expected && (storage == reply)) { + reply_expected = false; + reply_received = true; + reply = (msg_t *) NULL; + visible_msg = false; + } else { + storage->msg_class = rx().msg_class; + storage->msg_id = rx().msg_id; + if (storage->length > rx().length) + storage->length = rx().length; + } + storage = (msg_t *) NULL; + } + } + + return visible_msg; + +} // rxEnd + +//--------------------------------------------------------- + +static char toHexDigit( uint8_t val ) +{ + val &= 0x0F; + return (val >= 10) ? ((val - 10) + 'A') : (val + '0'); +} + +//--------------------------------------------------------- + +ubloxGPS::decode_t ubloxGPS::decode( char c ) +{ + decode_t res = DECODE_CHR_OK; + uint8_t chr = c; + +//Serial.print( '-' ); +//Serial.print( rxState ); +//Serial.print( 'x' ); +//Serial.print( toHexDigit(c >> 4) ); +//Serial.print( toHexDigit(c) ); + + switch ((ubxState_t) rxState) { + + case UBX_IDLE: +//if ((c != '\r') && (c != '\n')) trace << toHexDigit(c >> 4) << toHexDigit(c); + if (chr == SYNC_1) + rxState = (rxState_t) UBX_SYNC2; + else + res = DECODE_CHR_INVALID; + break; + + + case UBX_SYNC2: + if (chr == SYNC_2) { +//Serial.print( '+' ); +//Serial.print( chr, HEX ); + rxBegin(); + rxState = (rxState_t) UBX_HEAD; + } else { + rxState = (rxState_t) UBX_IDLE; + } + break; + + case UBX_HEAD: +//if ((c != '\r') && (c != '\n')) trace << '&' << toHexDigit(c >> 4) << toHexDigit(c); + m_rx_msg.crc_a += chr; + m_rx_msg.crc_b += m_rx_msg.crc_a; + + switch (chrCount++) { + case 0: + rx().msg_class = (msg_class_t) chr; +//if ((uint8_t) chr < 0x10) +// NeoSerial.print( '0' ); +//NeoSerial.print( chr, HEX ); + break; + case 1: + rx().msg_id = (msg_id_t) chr; +//NeoSerial.print( '/' ); +//if ((uint8_t) chr < 0x10) +// NeoSerial.print( '0' ); +//NeoSerial.print( (uint8_t) chr, HEX ); +//NeoSerial.write( ' ' ); + break; + case 2: + rx().length = chr; + break; + case 3: + rx().length += chr << 8; + if (rx().length > 512) { + rxBegin(); + rxState = (rxState_t) UBX_IDLE; + } + chrCount = 0; + rxState = (rxState_t) UBX_RECEIVING_DATA; + + NMEAGPS_INIT_FIX(m_fix); + + if (rx().msg_class == UBX_ACK) { + if (ack_expected) + ack_same_as_sent = true; // so far... + } else if (reply_expected && rx().same_kind( *reply )) + storage = reply; + else + storage = storage_for( rx() ); + break; + } + break; + + case UBX_RECEIVING_DATA: +//trace << hex << chr; + m_rx_msg.crc_a += chr; + m_rx_msg.crc_b += m_rx_msg.crc_a; + + if (storage && (chrCount < storage->length)) + ((uint8_t *)storage)[ sizeof(msg_t)+chrCount ] = chr; + + parseField( chr ); + + if (ack_same_as_sent) { + if (((chrCount == 0) && (sent.msg_class != (msg_class_t)chr)) || + ((chrCount == 1) && (sent.msg_id != (msg_id_t)chr))) + ack_same_as_sent = false; + } + + if (++chrCount >= rx().length) { + // payload size received + rxState = (rxState_t) UBX_CRC_A; + } + break; + + case UBX_CRC_A: + if (chr != m_rx_msg.crc_a) { + // All the values are suspect. Start over. + m_fix.valid.init(); + rx().msg_class = UBX_UNK; + #ifdef NMEAGPS_STATS + statistics.errors++; + #endif + } + rxState = (rxState_t) UBX_CRC_B; + break; + + case UBX_CRC_B: + if (chr != m_rx_msg.crc_b) { + // All the values are suspect. Start over. + m_fix.valid.init(); + rx().msg_class = UBX_UNK; + #ifdef NMEAGPS_STATS + statistics.errors++; + #endif + } else if (rxEnd()) { + res = DECODE_COMPLETED; + #ifdef NMEAGPS_STATS + statistics.ok++; + #endif + // This implements coherency. + intervalComplete( intervalCompleted() ); + } +//Serial.print( '!' ); + rxState = (rxState_t) UBX_IDLE; + break; + + default: + res = DECODE_CHR_INVALID; + break; + } + + if (res == DECODE_CHR_INVALID) { +//if ((c != '\r') && (c != '\n')) { +// Serial.print( 'x' ); +// Serial.print( toHexDigit(c >> 4) ); +// Serial.print( toHexDigit(c) ); +//} + if (rx().msg_class != UBX_UNK) + m_rx_msg.init(); + + // Delegate + res = NMEAGPS::decode( c ); + + } else { + #ifdef NMEAGPS_STATS + statistics.chars++; + #endif + } + + return res; + +} // decode + +//--------------------------------------------------------- + +void ubloxGPS::wait_for_idle() +{ + // Wait for the input buffer to be emptied + for (uint8_t waits=0; waits < 8; waits++) { + run(); + if (!receiving() || !waiting()) + break; + } + +} // wait_for_idle + +//--------------------------------------------------------- + +bool ubloxGPS::wait_for_ack() +{ + m_device->flush(); + + uint16_t sent = 0; + uint16_t idle_time = 0; + uint16_t removed_idle_time = 0; + + do { + if (receiving()) { + uint8_t rx_chars = m_device->available(); + wait_for_idle(); + sent = millis(); + + if (rx_chars) { + // If chars were received, decrease idle_time by the + // number of character times (TODO: use current baud rate) + + const uint16_t ms_per_charE5 = ((10UL * 1000) << 5) / 9600UL; + uint16_t rx_char_time = (rx_chars * ms_per_charE5) >> 5; + if (idle_time > rx_char_time) { + idle_time -= rx_char_time; + removed_idle_time += rx_char_time; + } else { + removed_idle_time += idle_time; + idle_time = 0; + } + } + + } else if (!waiting()) { + //Serial.print( F("a/r/n=") ); + //Serial.print( ack_received ); + //Serial.print( reply_received ); + //Serial.print( nak_received ); + //Serial.print( F(" -") ); + //Serial.println( removed_idle_time ); + + return ack_received || reply_received || !nak_received; + + } else { + // Idle, accumulate time + uint16_t ms = millis(); + if (sent != 0) + idle_time += ms-sent; + sent = ms; + run(); + } + } while ((idle_time < 300) && ((removed_idle_time+idle_time) < 1000)); + + //Serial.print( F("! -") ); + //Serial.println( removed_idle_time ); + + return false; + +} // wait_for_ack + +//--------------------------------------------------------- + +void ubloxGPS::write( const msg_t & msg ) +{ + m_device->print( (char) SYNC_1 ); + m_device->print( (char) SYNC_2 ); + + uint8_t crc_a = 0; + uint8_t crc_b = 0; + uint8_t *ptr = (uint8_t *) &msg; + uint16_t l = msg.length + sizeof(msg_t); + while (l--) + write( *ptr++, crc_a, crc_b ); + + m_device->print( (char) crc_a ); + m_device->print( (char) crc_b ); + + sent.msg_class = msg.msg_class; + sent.msg_id = msg.msg_id; +//trace << F("::write ") << msg.msg_class << F("/") << msg.msg_id << endl; +} + +//--------------------------------------------------------- + +void ubloxGPS::write_P( const msg_t & msg ) +{ + m_device->print( (char) SYNC_1 ); + m_device->print( (char) SYNC_2 ); + + uint8_t crc_a = 0; + uint8_t crc_b = 0; + uint8_t *ptr = (uint8_t *) &msg; + uint16_t l = pgm_read_word( &msg.length ) + sizeof(msg_t); + uint32_t dword; + + while (l > 0) { + if (l >= sizeof(dword)) { + l -= sizeof(dword); + dword = pgm_read_dword( ptr ); + for (uint8_t i=sizeof(dword); i--;) { + write( (uint8_t) dword, crc_a, crc_b ); + dword >>= 8; + } + ptr += sizeof(dword); + + } else { + write( pgm_read_byte( ptr++ ), crc_a, crc_b ); + l--; + } + } + + m_device->print( (char) crc_a ); + m_device->print( (char) crc_b ); + + sent.msg_class = (msg_class_t) pgm_read_byte( &msg.msg_class ); + sent.msg_id = (msg_id_t) pgm_read_byte( &msg.msg_id ); + +} // write + +//--------------------------------------------------------- +// Sends UBX command and optionally waits for the ack. + +bool ubloxGPS::send( const msg_t & msg, msg_t *reply_msg ) +{ +//trace << F("::send - ") << (uint8_t) msg.msg_class << F(" ") << (uint8_t) msg.msg_id << F(" "); + bool ok = true; + + write( msg ); + + if (msg.msg_class == UBX_CFG) { + ack_received = false; + nak_received = false; + ack_same_as_sent = false; + ack_expected = true; + } + + if (reply_msg) { + reply = reply_msg; + reply_received = false; + reply_expected = true; + } + + if (waiting()) { + ok = wait_for_ack(); + + #if 0 + Serial.print( F("wait_for_ack ") ); + if (ok) + Serial.print( F("ok! ") ); + else + Serial.print( F("failed! ") ); + if (ack_received) + Serial.println( F("ACK!") ); + else if (nak_received) + Serial.println( F("NAK!") ); + #endif + } + + return ok; + +} // send + +//--------------------------------------------------------- + +bool ubloxGPS::send_P( const msg_t & msg, msg_t *reply_msg ) +{ + return false; + +} // send_P + +//--------------------------------------------- + +bool ubloxGPS::parseField( char c ) +{ + if ((nmeaMessage != NMEAGPS::NMEA_UNKNOWN) && (nmeaMessage != UBX_MSG)) + return NMEAGPS::parseField( c ); + + uint8_t chr = c; + + switch (rx().msg_class) { + + case UBX_NAV: //================================================= +//if (chrCount == 0) Serial << F( " NAV ") << (uint8_t) rx().msg_id; + switch (rx().msg_id) { + case UBX_NAV_STATUS : return parseNavStatus ( chr ); + case UBX_NAV_POSLLH : return parseNavPosLLH ( chr ); + case UBX_NAV_DOP : return parseNavDOP ( chr ); + case UBX_NAV_VELNED : return parseNavVelNED ( chr ); + case UBX_NAV_TIMEGPS: return parseNavTimeGPS( chr ); + case UBX_NAV_TIMEUTC: return parseNavTimeUTC( chr ); + case UBX_NAV_SVINFO : return parseNavSVInfo ( chr ); + default : break; + } + break; + case UBX_HNR: //================================================= + switch (rx().msg_id) { + case UBX_HNR_PVT : return parseHnrPvt( chr ); + default : break; + } + break; + case UBX_RXM: //================================================= + case UBX_INF: //================================================= + case UBX_ACK: //================================================= + break; + case UBX_CFG: //================================================= + switch (rx().msg_id) { + case UBX_CFG_MSG: //-------------------------------------- + #ifdef UBLOX_PARSE_CFGMSG + #endif + break; + case UBX_CFG_RATE: //-------------------------------------- + #ifdef UBLOX_PARSE_CFGRATE + #endif + break; + case UBX_CFG_NAV5: //-------------------------------------- + #ifdef UBLOX_PARSE_CFGNAV5 + #endif + break; + default: + break; + } + break; + case UBX_MON: //================================================= + switch (rx().msg_id) { + case UBX_MON_VER: + #ifdef UBLOX_PARSE_MONVER + #endif + break; + default: + break; + } + break; + case UBX_AID: //================================================= + case UBX_TIM: //================================================= + case UBX_NMEA: //================================================= + break; + default: + break; + } + + return true; + +} // parseField + +//--------------------------------------------------------- + +bool ubloxGPS::parseNavStatus( uint8_t chr ) +{ + bool ok = true; + +//if (chrCount == 0) trace << F( "stat "); + #ifdef UBLOX_PARSE_STATUS + switch (chrCount) { + case 0: case 1: case 2: case 3: + ok = parseTOW( chr ); + break; + case 4: + ok = parseFix( chr ); + break; + case 5: + { + ublox::nav_status_t::flags_t flags = *((ublox::nav_status_t::flags_t *) &chr); + m_fix.status = ublox::nav_status_t::to_status( m_fix.status, flags ); +//trace << m_fix.status << ' '; + } + break; + } + #endif + + return ok; + +} // parseNavStatus + +//--------------------------------------------------------- + +bool ubloxGPS::parseNavDOP ( uint8_t chr ) +{ + bool ok = true; + +//if (chrCount == 0) Serial.print( F( "dop ") ); + #ifdef UBLOX_PARSE_DOP + switch (chrCount) { + case 0: case 1: case 2: case 3: + ok = parseTOW( chr ); + break; + + #ifdef GPS_FIX_PDOP + case 6: + NMEAGPS_INVALIDATE( pdop ); + m_fix.pdop = chr; + break; + case 7: + ((uint8_t *)&m_fix.pdop) [1] = chr; + m_fix.pdop *= 10; + m_fix.valid.pdop = true; + break; + #endif + + #ifdef GPS_FIX_VDOP + case 10: + NMEAGPS_INVALIDATE( vdop ); + m_fix.vdop = chr; + break; + case 11: + ((uint8_t *)&m_fix.vdop) [1] = chr; + m_fix.vdop *= 10; + m_fix.valid.vdop = true; + break; + #endif + + #ifdef GPS_FIX_HDOP + case 12: + NMEAGPS_INVALIDATE( hdop ); + m_fix.hdop = chr; + break; + case 13: + ((uint8_t *)&m_fix.hdop) [1] = chr; + m_fix.hdop *= 10; + m_fix.valid.hdop = true; + break; + #endif + + } + #endif + + return ok; + +} // parseNavDOP + +//--------------------------------------------------------- + +bool ubloxGPS::parseNavPosLLH( uint8_t chr ) +{ + bool ok = true; + +//if (chrCount == 0) trace << F( "velned "); + #ifdef UBLOX_PARSE_POSLLH + switch (chrCount) { + + case 0: case 1: case 2: case 3: + ok = parseTOW( chr ); + break; + + #if defined( GPS_FIX_LOCATION ) | defined( GPS_FIX_LOCATION_DMS ) + case 4: + NMEAGPS_INVALIDATE( location ); + case 5: case 6: case 7: + #ifdef GPS_FIX_LOCATION + ((uint8_t *)&m_fix.location._lon) [ chrCount-4 ] = chr; + #else + scratchpad.U1[ chrCount-4 ] = chr; + #endif + if (chrCount == 7) { + #if defined( GPS_FIX_LOCATION ) & defined( GPS_FIX_LOCATION_DMS ) + m_fix.longitudeDMS.From( m_fix.location._lon ); + #elif defined( GPS_FIX_LOCATION_DMS ) + m_fix.longitudeDMS.From( scratchpad.U4 ); + #endif + } + break; + case 8: case 9: case 10: case 11: + #ifdef GPS_FIX_LOCATION + ((uint8_t *)&m_fix.location._lat) [ chrCount-8 ] = chr; + #else + scratchpad.U1[ chrCount-8 ] = chr; + #endif + if (chrCount == 11) { + #if defined( GPS_FIX_LOCATION ) & defined( GPS_FIX_LOCATION_DMS ) + m_fix.latitudeDMS .From( m_fix.location._lat ); + #elif defined( GPS_FIX_LOCATION_DMS ) + m_fix.latitudeDMS .From( scratchpad.U4 ); + #endif + m_fix.valid.location = true; + } + break; + #endif + + #ifdef GPS_FIX_ALTITUDE + case 16: + NMEAGPS_INVALIDATE( altitude ); + case 17: case 18: case 19: + ((uint8_t *)&m_fix.alt) [ chrCount-16 ] = chr; + if (chrCount == 19) { + gps_fix::whole_frac *altp = &m_fix.alt; + int32_t height_MSLmm = *((int32_t *)altp); +//trace << F(" alt = ") << height_MSLmm; + m_fix.alt.whole = height_MSLmm / 1000UL; + m_fix.alt.frac = ((uint16_t)(height_MSLmm - (m_fix.alt.whole * 1000UL)))/10; +//trace << F(" = ") << m_fix.alt.whole << F("."); +//if (m_fix.alt.frac < 10) trace << '0'; +//trace << m_fix.alt.frac; + m_fix.valid.altitude = true; + } + break; + #endif + + #if defined( GPS_FIX_LAT_ERR ) | defined( GPS_FIX_LON_ERR ) + case 20: + #ifdef GPS_FIX_LAT_ERR + NMEAGPS_INVALIDATE( lat_err ); + #endif + + #ifdef GPS_FIX_LON_ERR + NMEAGPS_INVALIDATE( lon_err ); + #endif + // fall through... + case 21: case 22: case 23: + scratchpad.U1[ chrCount-20 ] = chr; + if (chrCount == 23) { + uint16_t err_cm = scratchpad.U4/100; + + #ifdef GPS_FIX_LAT_ERR + m_fix.lat_err_cm = err_cm; + m_fix.valid.lat_err = true; + #endif + + #ifdef GPS_FIX_LON_ERR + m_fix.lon_err_cm = err_cm; + m_fix.valid.lon_err = true; + #endif + } + break; + #endif + + #ifdef GPS_FIX_ALT_ERR + case 24: + NMEAGPS_INVALIDATE( alt_err ); + case 25: case 26: case 27: + scratchpad.U1[ chrCount-24 ] = chr; + if (chrCount == 27) { + m_fix.alt_err_cm = scratchpad.U4/100; + m_fix.valid.alt_err = true; + } + break; + #endif + } + #endif + + return ok; + +} // parseNavPosLLH + +//--------------------------------------------------------- + +bool ubloxGPS::parseNavVelNED( uint8_t chr ) +{ + bool ok = true; + +//if (chrCount == 0) trace << F( "velned "); + #ifdef UBLOX_PARSE_VELNED + switch (chrCount) { + + case 0: case 1: case 2: case 3: + ok = parseTOW( chr ); + break; + + #ifdef GPS_FIX_SPEED + // Use the speed_3D field at offset 20 + case 20: + NMEAGPS_INVALIDATE( speed ); + case 21: case 22: case 23: + // Temporarily store the 32-bit cm/s in the spd member + ((uint8_t *)&m_fix.spd) [ chrCount-20 ] = chr; + + if (chrCount == 23) { + gps_fix::whole_frac *spdp = &m_fix.spd; +//trace << F("spd = "); +//trace << (*((uint32_t *)spdp)); +//trace << F(" cm/s, "); + // Convert the 32-bit cm/s to nautical miles per hour + // (actually, 1000nmi/h limit is 51444, a 16-bit cm/s) + // Conversion factor: + // = cm/s * (3600s/1hr) * (1m/100cm) * (1nmi/1852m) + // = cm/s * 36/1852 + // = cm/s * 0.0194384449 + // Fixed point math: + // 0.0194384449 * 2^19 = 10191.343 (14 bits) + + const uint32_t FACTOR_E19 = 10191UL; + uint32_t nmiph_E19 = (*((uint32_t *)spdp) * FACTOR_E19); + m_fix.spd.whole = (nmiph_E19 >> 19); + + // remove whole part, leaving fractional part + nmiph_E19 -= ((uint32_t)m_fix.spd.whole) << 19; + + //m_fix.spd.frac = (nmiph_E19 * 1000UL) >> 19; + m_fix.spd.frac = (nmiph_E19 * 125) >> 16; + + m_fix.valid.speed = true; +//trace << m_fix.speed_mkn() << F(" nmi/h "); + } + break; + #endif + + #ifdef GPS_FIX_HEADING + case 24: + NMEAGPS_INVALIDATE( heading ); + case 25: case 26: case 27: + ((uint8_t *)&m_fix.hdg) [ chrCount-24 ] = chr; + if (chrCount == 27) { + gps_fix::whole_frac *hdgp = &m_fix.hdg; + uint32_t ui = *((uint32_t *)hdgp); +//trace << F("hdg "); +//trace << ui; +//trace << F("E-5, "); + + m_fix.hdg.whole = ui / 100000UL; + ui -= ((uint32_t)m_fix.hdg.whole) * 100000UL; + m_fix.hdg.frac = (ui/1000UL); // hundredths + m_fix.valid.heading = true; +//trace << m_fix.heading_cd() << F("E-2 "); + } + break; + #endif + } + #endif + + return ok; + +} // parseVelNED + +//--------------------------------------------------------- + +bool ubloxGPS::parseNavTimeGPS( uint8_t chr ) +{ + bool ok = true; + +//if (chrCount == 0) trace << F( "timegps "); + #ifdef UBLOX_PARSE_TIMEGPS + switch (chrCount) { + + #if defined(GPS_FIX_TIME) & defined(GPS_FIX_DATE) + case 0: case 1: case 2: case 3: + ok = parseTOW( chr ); + break; + case 10: + GPSTime::leap_seconds = (int8_t) chr; + break; + case 11: + { + ublox::nav_timegps_t::valid_t &v = + *((ublox::nav_timegps_t::valid_t *) &chr); + if (!v.leap_seconds) + GPSTime::leap_seconds = 0; // oops! +//else trace << F("leap ") << GPSTime::leap_seconds << ' '; + if (GPSTime::leap_seconds != 0) { + if (!v.time_of_week) { + m_fix.valid.date = + m_fix.valid.time = false; + } else if ((GPSTime::start_of_week() == 0) && + m_fix.valid.date && m_fix.valid.time) { + GPSTime::start_of_week( m_fix.dateTime ); +//trace << m_fix.dateTime << '.' << m_fix.dateTime_cs; + } + } + } + break; + #endif + } + #endif + + return ok; + +} // parseNavTimeGPS + +//--------------------------------------------------------- + +bool ubloxGPS::parseNavTimeUTC( uint8_t chr ) +{ + bool ok = true; + +//if (chrCount == 0) trace << F( " timeUTC "); + #ifdef UBLOX_PARSE_TIMEUTC + #if defined(GPS_FIX_TIME) | defined(GPS_FIX_DATE) + switch (chrCount) { + + #if defined(GPS_FIX_DATE) + case 12: NMEAGPS_INVALIDATE( date ); + m_fix.dateTime.year = chr; break; + case 13: m_fix.dateTime.year = + ((((uint16_t)chr) << 8) + m_fix.dateTime.year) % 100; + break; + case 14: m_fix.dateTime.month = chr; break; + case 15: m_fix.dateTime.date = chr; break; + #endif + + #if defined(GPS_FIX_TIME) + case 16: NMEAGPS_INVALIDATE( time ); + m_fix.dateTime.hours = chr; break; + case 17: m_fix.dateTime.minutes = chr; break; + case 18: m_fix.dateTime.seconds = chr; break; + #endif + + case 19: + { + ublox::nav_timeutc_t::valid_t &v = + *((ublox::nav_timeutc_t::valid_t *) &chr); + + #if defined(GPS_FIX_DATE) + m_fix.valid.date = (v.UTC & v.time_of_week); + #endif + #if defined(GPS_FIX_TIME) + m_fix.valid.time = (v.UTC & v.time_of_week); + #endif + + #if defined(GPS_FIX_TIME) & defined(GPS_FIX_DATE) + if (m_fix.valid.date && + (GPSTime::start_of_week() == 0) && + (GPSTime::leap_seconds != 0)) + GPSTime::start_of_week( m_fix.dateTime ); + #endif +//trace << m_fix.dateTime << F(".") << m_fix.dateTime_cs; +//trace << ' ' << v.UTC << ' ' << v.time_of_week << ' ' << start_of_week(); + } + break; + } + #endif + #endif + + return ok; + +} // parseNavTimeUTC + +//--------------------------------------------------------- + +bool ubloxGPS::parseNavSVInfo( uint8_t chr ) +{ + bool ok = true; + +//if (chrCount == 0) trace << F("svinfo "); + #ifdef UBLOX_PARSE_SVINFO + switch (chrCount) { + + case 0: case 1: case 2: case 3: + ok = parseTOW( chr ); + break; + + #ifdef GPS_FIX_SATELLITES + case 4: + m_fix.satellites = chr; + m_fix.valid.satellites = true; + + #ifdef NMEAGPS_PARSE_SATELLITES + sat_count = 0; + break; + default: + if ((chrCount >= 8) && (sat_count < NMEAGPS_MAX_SATELLITES)) { + uint8_t i = + (uint8_t) (chrCount - 8 - (12 * (uint16_t)sat_count)); + + switch (i) { + case 1: satellites[sat_count].id = chr; break; + + #ifdef NMEAGPS_PARSE_SATELLITE_INFO + case 0: satellites[sat_count].tracked = (chr != 255); break; + case 4: satellites[sat_count].snr = chr; break; + case 5: satellites[sat_count].elevation = chr; break; + case 6: satellites[sat_count].azimuth = chr; break; + case 7: + satellites[sat_count].azimuth += (chr << 8); + break; + #endif + + case 11: sat_count++; break; + } + } + #endif + break; + #endif + } + #endif + + return ok; + +} // parseNavSVInfo + +//--------------------------------------------------------- + +bool ubloxGPS::parseHnrPvt( uint8_t chr ) +{ + bool ok = true; + +#ifdef UBLOX_PARSE_HNR_PVT + switch (chrCount) { + + case 0: case 1: case 2: case 3: + ok = parseTOW( chr ); + break; + +#if defined(GPS_FIX_DATE) + case 4: + NMEAGPS_INVALIDATE( date ); + m_fix.dateTime.year = chr; + break; + case 5: m_fix.dateTime.year = ((((uint16_t)chr) << 8) + m_fix.dateTime.year) % 100; break; + case 6: m_fix.dateTime.month = chr; break; + case 7: m_fix.dateTime.date = chr; break; +#endif + +#if defined(GPS_FIX_TIME) + case 8: + NMEAGPS_INVALIDATE( time ); + m_fix.dateTime.hours = chr; + break; + case 9: m_fix.dateTime.minutes = chr; break; + case 10: m_fix.dateTime.seconds = chr; break; +#endif + + case 11: + { + ublox::hnr_pvt_t::valid_t &v = *((ublox::hnr_pvt_t::valid_t *) &chr); +#if defined(GPS_FIX_DATE) + m_fix.valid.date = (v.date); +#endif +#if defined(GPS_FIX_TIME) + m_fix.valid.time = (v.time); +#endif +#if defined(GPS_FIX_TIME) & defined(GPS_FIX_DATE) + if (m_fix.valid.date && v.fully_resolved && (GPSTime::start_of_week() == 0) && (GPSTime::leap_seconds != 0)) + { + GPSTime::start_of_week( m_fix.dateTime ); + } +#endif + break; + } + + case 16: + ok = parseFix( chr ); + break; + case 17: + { + ublox::hnr_pvt_t::flags_t flags = *((ublox::hnr_pvt_t::flags_t *) &chr); + m_fix.status = ublox::hnr_pvt_t::to_status( m_fix.status, flags ); + break; + } + +#if defined( GPS_FIX_LOCATION ) | defined( GPS_FIX_LOCATION_DMS ) + case 20: + NMEAGPS_INVALIDATE( location ); + case 21: case 22: case 23: +#ifdef GPS_FIX_LOCATION + ((uint8_t *)&m_fix.location._lon) [ chrCount-20 ] = chr; +#else + scratchpad.U1[ chrCount-20 ] = chr; +#endif + if (chrCount == 23) { +#if defined( GPS_FIX_LOCATION ) & defined( GPS_FIX_LOCATION_DMS ) + m_fix.longitudeDMS.From( m_fix.location._lon ); +#elif defined( GPS_FIX_LOCATION_DMS ) + m_fix.longitudeDMS.From( scratchpad.U4 ); +#endif + } + break; + case 24: case 25: case 26: case 27: +#ifdef GPS_FIX_LOCATION + ((uint8_t *)&m_fix.location._lat) [ chrCount-24 ] = chr; +#else + scratchpad.U1[ chrCount-24 ] = chr; +#endif + if (chrCount == 27) { +#if defined( GPS_FIX_LOCATION ) & defined( GPS_FIX_LOCATION_DMS ) + m_fix.latitudeDMS .From( m_fix.location._lat ); +#elif defined( GPS_FIX_LOCATION_DMS ) + m_fix.latitudeDMS .From( scratchpad.U4 ); +#endif + m_fix.valid.location = true; + } + break; +#endif + +#ifdef GPS_FIX_ALTITUDE + case 32: + NMEAGPS_INVALIDATE( altitude ); + case 33: case 34: case 35: + ((uint8_t *)&m_fix.alt) [ chrCount-21 ] = chr; + if (chrCount == 35) { + gps_fix::whole_frac *altp = &m_fix.alt; + int32_t height_MSLmm = *((int32_t *)altp); + m_fix.alt.whole = height_MSLmm / 1000UL; + m_fix.alt.frac = ((uint16_t)(height_MSLmm - (m_fix.alt.whole * 1000UL)))/10; + m_fix.valid.altitude = true; + } + break; +#endif + +#ifdef GPS_FIX_SPEED + // Use the speed_3D field at offset 40 + case 40: + NMEAGPS_INVALIDATE( speed ); + case 41: case 42: case 43: + // Temporarily store the 32-bit cm/s in the spd member + ((uint8_t *)&m_fix.spd) [ chrCount-40 ] = chr; + if (chrCount == 43) { + gps_fix::whole_frac *spdp = &m_fix.spd; + // Convert the 32-bit mm/s to nautical miles per hour + // Conversion factor: + // = mm/s * (3600s/1hr) * (1m/1000mm) * (1nmi/1852m) + // = mm/s * 36/18520 + // = mm/s * 0.00194384449 + // Fixed point math: + // 0.00194384449 * 2^19 = 1019.1343 (14 bits) + const uint32_t FACTOR_E19 = 1019UL; + uint32_t nmiph_E19 = (*((uint32_t *)spdp) * FACTOR_E19); + m_fix.spd.whole = (nmiph_E19 >> 19); + // remove whole part, leaving fractional part + nmiph_E19 -= ((uint32_t)m_fix.spd.whole) << 19; + m_fix.spd.frac = (nmiph_E19 * 125) >> 16; + m_fix.valid.speed = true; + } + break; +#endif + +#ifdef GPS_FIX_HEADING + case 44: + NMEAGPS_INVALIDATE( heading ); + case 45: case 46: case 47: + ((uint8_t *)&m_fix.hdg) [ chrCount-44 ] = chr; + if (chrCount == 47) { + gps_fix::whole_frac *hdgp = &m_fix.hdg; + uint32_t ui = *((uint32_t *)hdgp); + m_fix.hdg.whole = ui / 100000UL; + ui -= ((uint32_t)m_fix.hdg.whole) * 100000UL; + m_fix.hdg.frac = (ui/1000UL); // hundredths + m_fix.valid.heading = true; + } + break; +#endif + +#if defined( GPS_FIX_LAT_ERR ) | defined( GPS_FIX_LON_ERR ) + case 52: +#ifdef GPS_FIX_LAT_ERR + NMEAGPS_INVALIDATE( lat_err ); +#endif +#ifdef GPS_FIX_LON_ERR + NMEAGPS_INVALIDATE( lon_err ); +#endif + // fall through... + case 53: case 54: case 55: + scratchpad.U1[ chrCount-52 ] = chr; + if (chrCount == 55) { + uint16_t err_cm = scratchpad.U4/100; +#ifdef GPS_FIX_LAT_ERR + m_fix.lat_err_cm = err_cm; + m_fix.valid.lat_err = true; +#endif +#ifdef GPS_FIX_LON_ERR + m_fix.lon_err_cm = err_cm; + m_fix.valid.lon_err = true; +#endif + } + break; +#endif + +#ifdef GPS_FIX_ALT_ERR + case 56: + NMEAGPS_INVALIDATE( alt_err ); + case 57: case 58: case 59: + scratchpad.U1[ chrCount-56 ] = chr; + if (chrCount == 59) { + m_fix.alt_err_cm = scratchpad.U4/100; + m_fix.valid.alt_err = true; + } + break; +#endif + + } +#endif + + return ok; + +} // parseHnrPvt + +//--------------------------------------------------------- + +bool ubloxGPS::parseFix( uint8_t c ) +{ + static const gps_fix::status_t ubx[] __PROGMEM = + { + gps_fix::STATUS_NONE, + gps_fix::STATUS_EST, // dead reckoning only + gps_fix::STATUS_STD, // 2D + gps_fix::STATUS_STD, // 3D + gps_fix::STATUS_STD, // GPS + dead reckoning + gps_fix::STATUS_TIME_ONLY + }; + + if (c >= sizeof(ubx)/sizeof(ubx[0])) + return false; + + m_fix.status = (gps_fix::status_t) pgm_read_byte( &ubx[c] ); + m_fix.valid.status = true; + + return true; + +} // parseFix + +#if 0 + static const uint8_t cfg_msg_data[] __PROGMEM = + { ubloxGPS::UBX_CFG, ubloxGPS::UBX_CFG_MSG, + sizeof(ubloxGPS::cfg_msg_t), 0, + ubloxGPS::UBX_NMEA, NMEAGPS::NMEA_VTG, 0 }; + + static const ubloxGPS::cfg_msg_t *cfg_msg_P = + (const ubloxGPS::cfg_msg_t *) &cfg_msg_data[0]; + + send_P( *cfg_msg_P ); + + const ubloxGPS::msg_hdr_t test __PROGMEM = + { ubloxGPS::UBX_CFG, ubloxGPS::UBX_CFG_RATE }; + + const uint8_t test2_data[] __PROGMEM = + { ubloxGPS::UBX_CFG, ubloxGPS::UBX_CFG_RATE, + sizeof(ubloxGPS::cfg_rate_t), 0, + 0xE8, 0x03, 0x01, 0x00, ubloxGPS::UBX_TIME_REF_GPS, 0 }; + + const ubloxGPS::msg_t *test2 = (const ubloxGPS::msg_t *) &test2_data[0]; +#endif + +#endif // NMEAGPS_DERIVED_TYPES enabled diff --git a/software/firmware/libraries/NeoGPS/src/ublox/ubxGPS.h b/software/firmware/libraries/NeoGPS/src/ublox/ubxGPS.h new file mode 100644 index 0000000..f052034 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/src/ublox/ubxGPS.h @@ -0,0 +1,332 @@ +#ifndef _UBXGPS_H_ +#define _UBXGPS_H_ + +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . + +#include "NMEAGPS_cfg.h" +// Disable the entire file if derived types are not allowed. +#ifdef NMEAGPS_DERIVED_TYPES + +#include "ublox/ubxNMEA.h" +#include "ublox/ubxmsg.h" +#include "GPSTime.h" +#include "ublox/ubx_cfg.h" + +#include +#include + +// NOTE: millis() is used for ACK timing + + +class ubloxGPS : public ubloxNMEA +{ + ubloxGPS & operator =( const ubloxGPS & ); + ubloxGPS( const ubloxGPS & ); + +public: + + // Constructor needs to know the device to handle the UBX binary protocol + ubloxGPS( Stream *device ) + : + storage( (ublox::msg_t *) NULL ), + reply( (ublox::msg_t *) NULL ), + reply_expected( false ), + ack_expected( false ), + m_device( device ) + {}; + + // ublox binary UBX message type. + enum ubx_msg_t { + UBX_MSG = PUBX_LAST_MSG+1 + }; + static const nmea_msg_t UBX_FIRST_MSG = (nmea_msg_t) UBX_MSG; + static const nmea_msg_t UBX_LAST_MSG = (nmea_msg_t) UBX_MSG; + + + //................................................................ + // Process one character of ublox message. The internal state + // machine tracks what part of the sentence has been received. As the + // tracks what part of the sentence has been received so far. As the + // sentence is received, members of the /fix/ structure are updated. + // @return DECODE_COMPLETED when a sentence has been completely received. + + decode_t decode( char c ); + + //................................................................ + // Received message header. Payload is only stored if /storage/ is + // overridden for that message type. This is the UBX-specific + // version of "nmeaMessage". + + ublox::msg_t & rx() { return m_rx_msg; } + + //................................................................ + + bool enable_msg( ublox::msg_class_t msg_class, ublox::msg_id_t msg_id ) + { + return send( ublox::cfg_msg_t( msg_class, msg_id, 1 ) ); + } + + bool disable_msg( ublox::msg_class_t msg_class, ublox::msg_id_t msg_id ) + { + return send( ublox::cfg_msg_t( msg_class, msg_id, 0 ) ); + } + + //................................................................ + // Send a message (non-blocking). + // Although multiple /send_request/s can be issued, + // all replies will be handled identically. + + bool send_request( const ublox::msg_t & msg ) + { + write( msg ); + return true; + } + + bool send_request_P( const ublox::msg_t & msg ) + { + write_P( msg ); + return true; + } + + //................................................................ + // Send a message and wait for a reply (blocking). + // No event will be generated for the reply. + // If /msg/ is a UBX_CFG, this will wait for a UBX_CFG_ACK/NAK + // and return true if ACKed. + // If /msg/ is a poll, this will wait for the reply. + // If /msg/ is neither, this will return true immediately. + // If /msg/ is both, this will wait for both the reply and the ACK/NAK. + // If /storage_for/ is implemented, those messages will continue + // to be saved while waiting for this reply. + + bool send( const ublox::msg_t & msg, ublox::msg_t *reply_msg = (ublox::msg_t *) NULL ); + bool send_P( const ublox::msg_t & msg, ublox::msg_t *reply_msg = (ublox::msg_t *) NULL ); + using NMEAGPS::send_P; + + //................................................................ + // Ask for a specific message (non-blocking). + // The message will receive be received later. + // See also /send_request/. + + bool poll_request( const ublox::msg_t & msg ) + { + ublox::msg_t poll_msg( msg.msg_class, msg.msg_id, 0 ); + return send_request( poll_msg ); + } + + bool poll_request_P( const ublox::msg_t & msg ) + { + ublox::msg_t poll_msg( (ublox::msg_class_t) pgm_read_byte( &msg.msg_class ), + (ublox::msg_id_t) pgm_read_byte( &msg.msg_id ), 0 ); + return send_request( poll_msg ); + } + + //................................................................ + // Ask for a specific message (blocking). + // See also /send/. + bool poll( ublox::msg_t & msg ) + { + ublox::msg_t poll_msg( msg.msg_class, msg.msg_id, 0 ); + return send( poll_msg, &msg ); + } + + bool poll_P( const ublox::msg_t & msg, ublox::msg_t *reply_msg = (ublox::msg_t *) NULL ) + { + ublox::msg_t poll_msg( (ublox::msg_class_t) pgm_read_byte( &msg.msg_class ), + (ublox::msg_id_t) pgm_read_byte( &msg.msg_id ), 0 ); + return send( poll_msg, reply_msg ); + } + + //................................................................ + // Return the Stream that was passed into the constructor. + + Stream *Device() const { return (Stream *)m_device; }; + +protected: + + /* + * Some UBX messages can be larger than 256 bytes, so + * hide the 8-bit NMEAGPS::chrCount with this 16-bit version. + */ + uint16_t chrCount; + + bool parseField( char chr ); + + enum ubxState_t { + UBX_IDLE = NMEA_IDLE, + UBX_SYNC2 = NMEA_LAST_STATE+1, + UBX_HEAD, + UBX_RECEIVING_DATA, + UBX_CRC_A, + UBX_CRC_B + }; + static const ubxState_t UBX_FIRST_STATE = UBX_SYNC2; + static const ubxState_t UBX_LAST_STATE = UBX_CRC_B; + + inline void write + ( uint8_t c, uint8_t & crc_a, uint8_t & crc_b ) const + { + m_device->print( (char) c ); + crc_a += c; + crc_b += crc_a; + }; + void write( const ublox::msg_t & msg ); + void write_P( const ublox::msg_t & msg ); + + //................................................................ + // When the processing style is polling (not interrupt), this + // should be called frequently by any internal methods that block + // to make sure received chars continue to be processed. + + virtual void run() + { + if (processing_style == PS_POLLING) + while (Device()->available()) + handle( Device()->read() ); + // else + // handled by interrupts + } + + void wait_for_idle(); + bool wait_for_ack(); + // NOTE: /run/ is called from these blocking functions + + + bool waiting() const + { + return (ack_expected && (!ack_received && !nak_received)) || + (reply_expected && !reply_received); + } + + bool receiving() const + { + return (rxState != (rxState_t)UBX_IDLE) || (m_device && m_device->available()); + } + + // Override this if the contents of a particular message need to be saved. + // This may execute in an interrupt context, so be quick! + // NOTE: the ublox::msg_t.length will get stepped on, so you may need to + // set it every time if you are using a union for your storage. + + virtual ublox::msg_t *storage_for( const ublox::msg_t & rx_msg ) + { return (ublox::msg_t *) NULL; } + + virtual bool intervalCompleted() const + { + return ((nmeaMessage == (nmea_msg_t) UBX_MSG) && + (m_rx_msg.msg_class == UBX_LAST_MSG_CLASS_IN_INTERVAL) && + (m_rx_msg.msg_id == UBX_LAST_MSG_ID_IN_INTERVAL)) + || + NMEAGPS::intervalCompleted(); + } + +private: + ublox::msg_t *storage; // cached ptr to hold a received msg. + + // Storage for a specific received message. + // Used internally by send & poll variants. + // Checked and used before /storage_for/ is called. + + ublox::msg_t *reply; + + struct { + bool reply_expected NEOGPS_BF(1); + bool reply_received NEOGPS_BF(1); + bool ack_expected NEOGPS_BF(1); + bool ack_received NEOGPS_BF(1); + bool nak_received NEOGPS_BF(1); + bool ack_same_as_sent NEOGPS_BF(1); + } NEOGPS_PACKED; + struct ublox::msg_hdr_t sent; + + struct rx_msg_t : ublox::msg_t + { + uint8_t crc_a; // accumulated as packet received + uint8_t crc_b; // accumulated as packet received + + rx_msg_t() + { + init(); + } + + void init() + { + msg_class = ublox::UBX_UNK; + msg_id = ublox::UBX_ID_UNK; + length = 0; + crc_a = 0; + crc_b = 0; + } + + } NEOGPS_PACKED; + + rx_msg_t m_rx_msg; + + void rxBegin(); + bool rxEnd(); + + static const uint8_t SYNC_1 = 0xB5; + static const uint8_t SYNC_2 = 0x62; + + Stream *m_device; + + bool parseNavStatus ( uint8_t chr ); + bool parseNavDOP ( uint8_t chr ); + bool parseNavPosLLH ( uint8_t chr ); + bool parseNavVelNED ( uint8_t chr ); + bool parseNavTimeGPS( uint8_t chr ); + bool parseNavTimeUTC( uint8_t chr ); + bool parseNavSVInfo ( uint8_t chr ); + + bool parseHnrPvt( uint8_t chr ); + + bool parseFix( uint8_t c ); + + bool parseTOW( uint8_t chr ) + { + #if defined(GPS_FIX_TIME) & defined(GPS_FIX_DATE) + if (chrCount == 0) { + m_fix.valid.date = + m_fix.valid.time = false; + } + + ((uint8_t *) &m_fix.dateTime)[ chrCount ] = chr; + + if (chrCount == 3) { + uint32_t tow = *((uint32_t *) &m_fix.dateTime); + //trace << PSTR("@ ") << tow; + + uint16_t ms; + if (GPSTime::from_TOWms( tow, m_fix.dateTime, ms )) { + m_fix.dateTime_cs = ms / 10; + m_fix.valid.time = true; + m_fix.valid.date = true; + } else + m_fix.dateTime.init(); + //trace << PSTR(".") << m_fix.dateTime_cs; + } + #endif + + return true; + } + +} NEOGPS_PACKED; + +#endif // NMEAGPS_DERIVED_TYPES enabled + +#endif diff --git a/software/firmware/libraries/NeoGPS/src/ublox/ubxNMEA.cpp b/software/firmware/libraries/NeoGPS/src/ublox/ubxNMEA.cpp new file mode 100644 index 0000000..4858a3c --- /dev/null +++ b/software/firmware/libraries/NeoGPS/src/ublox/ubxNMEA.cpp @@ -0,0 +1,147 @@ +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . + +#include "ublox/ubxNMEA.h" + +// Disable the entire file if derived types are not allowed. +#ifdef NMEAGPS_DERIVED_TYPES + +//--------------------------------------------- + +bool ubloxNMEA::parseField(char chr) +{ + if (nmeaMessage >= (nmea_msg_t) PUBX_FIRST_MSG) { + + switch (nmeaMessage) { + + case PUBX_00: return parsePUBX_00( chr ); + + #if defined(NMEAGPS_PARSE_PUBX_04) | defined(NMEAGPS_RECOGNIZE_ALL) + case PUBX_04: return parsePUBX_04( chr ); + #endif + + default: + break; + } + + } else + + // Delegate + return NMEAGPS::parseField(chr); + + + return true; + +} // parseField + +//---------------------------- + +bool ubloxNMEA::parsePUBX_00( char chr ) +{ + bool ok = true; + + switch (fieldIndex) { + case 1: + // The first field is actually a message subtype + if (chrCount == 0) + ok = (chr == '0'); + + else if (chrCount == 1) { + switch (chr) { + #if defined(NMEAGPS_PARSE_PUBX_00) | defined(NMEAGPS_RECOGNIZE_ALL) + case '0': break; + #endif + #if defined(NMEAGPS_PARSE_PUBX_04) | defined(NMEAGPS_RECOGNIZE_ALL) + case '4': nmeaMessage = (nmea_msg_t) PUBX_04; break; + #endif + default : ok = false; + } + + } else // chrCount > 1 + ok = (chr == ','); + break; + + #ifdef NMEAGPS_PARSE_PUBX_00 + case 2: return parseTime( chr ); + PARSE_LOC(3); + case 7: return parseAlt( chr ); + case 8: return parseFix( chr ); + case 11: return parseSpeed( chr ); // kph! + case 12: return parseHeading( chr ); + case 15: return parseHDOP( chr ); + case 16: return parseVDOP( chr ); + case 18: return parseSatellites( chr ); + #endif + } + + return ok; + +} // parsePUBX_00 + +//--------------------------------------------- + +bool ubloxNMEA::parsePUBX_04( char chr ) +{ + #ifdef NMEAGPS_PARSE_PUBX_04 + switch (fieldIndex) { + case 2: return parseTime( chr ); + case 3: return parseDDMMYY( chr ); + } + #endif + + return true; + +} // parsePUBX_04 + +//--------------------------------------------- + +bool ubloxNMEA::parseFix( char chr ) +{ + if (chrCount == 0) { + NMEAGPS_INVALIDATE( status ); + if (chr == 'N') + m_fix.status = gps_fix::STATUS_NONE; + else if (chr == 'T') + m_fix.status = gps_fix::STATUS_TIME_ONLY; + else if (chr == 'R') + m_fix.status = gps_fix::STATUS_EST; + else if (chr == 'G') + m_fix.status = gps_fix::STATUS_STD; + else if (chr == 'D') + m_fix.status = gps_fix::STATUS_DGPS; + + } else if (chrCount == 1) { + + if (((chr == 'T') && (m_fix.status == gps_fix::STATUS_TIME_ONLY)) || + ((chr == 'K') && (m_fix.status == gps_fix::STATUS_EST)) || + (((chr == '2') || (chr == '3')) && + ((m_fix.status == gps_fix::STATUS_STD) || + (m_fix.status == gps_fix::STATUS_DGPS))) || + ((chr == 'F') && (m_fix.status == gps_fix::STATUS_NONE))) + // status based on first char was ok guess + m_fix.valid.status = true; + + else if ((chr == 'R') && (m_fix.status == gps_fix::STATUS_DGPS)) { + m_fix.status = gps_fix::STATUS_EST; // oops, was DR instead + m_fix.valid.status = true; + } + } + + return true; +} + +#endif \ No newline at end of file diff --git a/software/firmware/libraries/NeoGPS/src/ublox/ubxNMEA.h b/software/firmware/libraries/NeoGPS/src/ublox/ubxNMEA.h new file mode 100644 index 0000000..5ce707e --- /dev/null +++ b/software/firmware/libraries/NeoGPS/src/ublox/ubxNMEA.h @@ -0,0 +1,110 @@ +#ifndef _UBXNMEA_H_ +#define _UBXNMEA_H_ + +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . + +#include "NMEAGPS_cfg.h" + +// Disable the entire file if derived types are not allowed. +#ifdef NMEAGPS_DERIVED_TYPES + +#include "NMEAGPS.h" + +//------------------------------------------------------------ +// Enable/disable the parsing of specific proprietary NMEA sentences. +// +// Configuring out a sentence prevents its fields from being parsed. +// However, the sentence type may still be recognized by /decode/ and +// stored in member /nmeaMessage/. No valid flags would be available. + +//#define NMEAGPS_PARSE_PUBX_00 +//#define NMEAGPS_PARSE_PUBX_04 + +// Ublox proprietary messages do not have a message type. These +// messages start with "$PUBX," which ends with the manufacturer ID. The +// message type is actually specified by the first numeric field. In order +// to parse these messages, /parse_mfr_ID/ must be overridden to set the +// /nmeaMessage/ to PUBX_00 during /parseCommand/. When the first numeric +// field is completed by /parseField/, it may change /nmeamessage/ to one +// of the other PUBX message types. + +#if (defined(NMEAGPS_PARSE_PUBX_00) | defined(NMEAGPS_PARSE_PUBX_04)) + + #if !defined(NMEAGPS_PARSE_PROPRIETARY) + #error NMEAGPS_PARSE_PROPRIETARY must be defined in NMEAGPS_cfg.h in order to parse PUBX messages! + #endif + + #if !defined(NMEAGPS_PARSE_MFR_ID) + #error NMEAGPS_PARSE_MFR_ID must be defined in NMEAGPS_cfg.h in order to parse PUBX messages! + #endif +#endif + +//============================================================= +// NMEA 0183 Parser for ublox Neo-6 GPS Modules. +// +// @section Limitations +// Very limited support for ublox proprietary NMEA messages. +// Only NMEA messages of types PUBX,00 and PUBX,04 are parsed. +// + +class ubloxNMEA : public NMEAGPS +{ + ubloxNMEA( const ubloxNMEA & ); + +public: + + ubloxNMEA() {}; + + /** ublox proprietary NMEA message types. */ + enum pubx_msg_t { + PUBX_00 = NMEA_LAST_MSG+1, + #if defined(NMEAGPS_PARSE_PUBX_04) | defined(NMEAGPS_RECOGNIZE_ALL) + PUBX_04, + #endif + PUBX_END + }; + static const nmea_msg_t PUBX_FIRST_MSG = (nmea_msg_t) PUBX_00; + static const nmea_msg_t PUBX_LAST_MSG = (nmea_msg_t) (PUBX_END-1); + +protected: + bool parseMfrID( char chr ) + { bool ok; + switch (chrCount) { + case 1: ok = (chr == 'U'); break; + case 2: ok = (chr == 'B'); break; + default: if (chr == 'X') { + ok = true; + nmeaMessage = (nmea_msg_t) PUBX_00; + } else + ok = false; + break; + } + return ok; + }; + + bool parsePUBX_00( char chr ); + bool parsePUBX_04( char chr ); + + bool parseField( char chr ); + + bool parseFix( char chr ); +} NEOGPS_PACKED; + +#endif // NMEAGPS_DERIVED_TYPES enabled + +#endif diff --git a/software/firmware/libraries/NeoGPS/src/ublox/ubx_cfg.h b/software/firmware/libraries/NeoGPS/src/ublox/ubx_cfg.h new file mode 100644 index 0000000..05880c1 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/src/ublox/ubx_cfg.h @@ -0,0 +1,64 @@ +#ifndef UBX_CFG_H +#define UBX_CFG_H + +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . + +//-------------------------------------------------------------------- +// Enable/disable the parsing of specific UBX messages. +// +// Configuring out a message prevents its fields from being parsed. +// However, the message type will still be recognized by /decode/ and +// stored in member /rx_msg/. No valid flags would be available. + +#define UBLOX_PARSE_STATUS +#define UBLOX_PARSE_TIMEGPS +#define UBLOX_PARSE_TIMEUTC +#define UBLOX_PARSE_POSLLH +//#define UBLOX_PARSE_DOP +#define UBLOX_PARSE_VELNED +//#define UBLOX_PARSE_SVINFO +//#define UBLOX_PARSE_CFGNAV5 +//#define UBLOX_PARSE_MONVER +//#define UBLOX_PARSE_HNR_PVT + +//-------------------------------------------------------------------- +// Identify the last UBX message in an update interval. +// (There are two parts to a UBX message, the class and the ID.) +// For coherency, you must determine which UBX message is last! +// This section *should* pick the correct last UBX message for NEO-6M devices. + +#if defined(UBLOX_PARSE_HNR_PVT) + #define UBX_LAST_MSG_CLASS_IN_INTERVAL ublox::UBX_HNR + #define UBX_LAST_MSG_ID_IN_INTERVAL ublox::UBX_HNR_PVT +#else + #define UBX_LAST_MSG_CLASS_IN_INTERVAL ublox::UBX_NAV + + #if defined(UBLOX_PARSE_DOP) + #define UBX_LAST_MSG_ID_IN_INTERVAL ublox::UBX_NAV_DOP + #elif defined(UBLOX_PARSE_VELNED) + #define UBX_LAST_MSG_ID_IN_INTERVAL ublox::UBX_NAV_VELNED + #elif defined(UBLOX_PARSE_POSLLH) + #define UBX_LAST_MSG_ID_IN_INTERVAL ublox::UBX_NAV_POSLLH + #elif defined(UBLOX_PARSE_SVINFO) + #define UBX_LAST_MSG_ID_IN_INTERVAL ublox::UBX_NAV_SVINFO + #else + #define UBX_LAST_MSG_ID_IN_INTERVAL ublox::UBX_NAV_STATUS + #endif +#endif + +#endif \ No newline at end of file diff --git a/software/firmware/libraries/NeoGPS/src/ublox/ubxmsg.cpp b/software/firmware/libraries/NeoGPS/src/ublox/ubxmsg.cpp new file mode 100644 index 0000000..2ac4f1a --- /dev/null +++ b/software/firmware/libraries/NeoGPS/src/ublox/ubxmsg.cpp @@ -0,0 +1,71 @@ +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . + +#include "ublox/ubxGPS.h" + +// Disable the entire file if derived types are not allowed. +#ifdef NMEAGPS_DERIVED_TYPES + +using namespace ublox; + +bool ublox::configNMEA( ubloxGPS &gps, NMEAGPS::nmea_msg_t msgType, uint8_t rate ) +{ + static const ubx_nmea_msg_t ubx[] __PROGMEM = { + #if defined(NMEAGPS_PARSE_GGA) | defined(NMEAGPS_RECOGNIZE_ALL) + UBX_GPGGA, + #endif + + #if defined(NMEAGPS_PARSE_GLL) | defined(NMEAGPS_RECOGNIZE_ALL) + UBX_GPGLL, + #endif + + #if defined(NMEAGPS_PARSE_GSA) | defined(NMEAGPS_RECOGNIZE_ALL) + UBX_GPGSA, + #endif + + #if defined(NMEAGPS_PARSE_GST) | defined(NMEAGPS_RECOGNIZE_ALL) + UBX_GPGST, + #endif + + #if defined(NMEAGPS_PARSE_GSV) | defined(NMEAGPS_RECOGNIZE_ALL) + UBX_GPGSV, + #endif + + #if defined(NMEAGPS_PARSE_RMC) | defined(NMEAGPS_RECOGNIZE_ALL) + UBX_GPRMC, + #endif + + #if defined(NMEAGPS_PARSE_VTG) | defined(NMEAGPS_RECOGNIZE_ALL) + UBX_GPVTG, + #endif + + #if defined(NMEAGPS_PARSE_ZDA) | defined(NMEAGPS_RECOGNIZE_ALL) + UBX_GPZDA, + #endif + }; + + uint8_t msg_index = (uint8_t) msgType - (uint8_t) NMEAGPS::NMEA_FIRST_MSG; + + if (msg_index >= sizeof(ubx)/sizeof(ubx[0])) + return false; + + msg_id_t msg_id = (msg_id_t) pgm_read_byte( &ubx[msg_index] ); + + return gps.send( cfg_msg_t( UBX_NMEA, msg_id, rate ) ); +} + +#endif \ No newline at end of file diff --git a/software/firmware/libraries/NeoGPS/src/ublox/ubxmsg.h b/software/firmware/libraries/NeoGPS/src/ublox/ubxmsg.h new file mode 100644 index 0000000..57cda43 --- /dev/null +++ b/software/firmware/libraries/NeoGPS/src/ublox/ubxmsg.h @@ -0,0 +1,589 @@ +#ifndef UBXMSG_H +#define UBXMSG_H + +// Copyright (C) 2014-2017, SlashDevin +// +// This file is part of NeoGPS +// +// NeoGPS is free software: you can redistribute it and/or modify +// it under the terms of the GNU General Public License as published by +// the Free Software Foundation, either version 3 of the License, or +// (at your option) any later version. +// +// NeoGPS is distributed in the hope that it will be useful, +// but WITHOUT ANY WARRANTY; without even the implied warranty of +// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +// GNU General Public License for more details. +// +// You should have received a copy of the GNU General Public License +// along with NeoGPS. If not, see . + +#include "NMEAGPS_cfg.h" + +// Disable the entire file if derived types are not allowed. +#ifdef NMEAGPS_DERIVED_TYPES + +#include "NMEAGPS.h" +class ubloxGPS; + +namespace ublox { + + enum msg_class_t + { UBX_NAV = 0x01, // Navigation results + UBX_RXM = 0x02, // Receiver Manager messages + UBX_INF = 0x04, // Informational messages + UBX_ACK = 0x05, // ACK/NAK replies to CFG messages + UBX_CFG = 0x06, // Configuration input messages + UBX_MON = 0x0A, // Monitoring messages + UBX_AID = 0x0B, // Assist Now aiding messages + UBX_TIM = 0x0D, // Timing messages + UBX_HNR = 0x28, // High rate navigation results + UBX_NMEA = 0xF0, // NMEA Standard messages + UBX_PUBX = 0xF1, // NMEA proprietary messages (PUBX) + UBX_UNK = 0xFF + } __attribute__((packed)); + + enum msg_id_t + { + UBX_ACK_NAK = 0x00, // Reply to CFG messages + UBX_ACK_ACK = 0x01, // Reply to CFG messages + UBX_CFG_MSG = 0x01, // Configure which messages to send + UBX_CFG_RST = 0x04, // Reset command + UBX_CFG_RATE = 0x08, // Configure message rate + UBX_CFG_NMEA = 0x17, // Configure NMEA protocol + UBX_CFG_NAV5 = 0x24, // Configure navigation engine settings + UBX_MON_VER = 0x04, // Monitor Receiver/Software version + UBX_NAV_POSLLH = 0x02, // Current Position + UBX_NAV_STATUS = 0x03, // Receiver Navigation Status + UBX_NAV_DOP = 0x04, // Dilutions of Precision + UBX_NAV_ODO = 0x09, // Odometer Solution (NEO-M8 only) + UBX_NAV_RESETODO = 0x10, // Reset Odometer (NEO-M8 only) + UBX_NAV_VELNED = 0x12, // Current Velocity + UBX_NAV_TIMEGPS = 0x20, // Current GPS Time + UBX_NAV_TIMEUTC = 0x21, // Current UTC Time + UBX_NAV_SVINFO = 0x30, // Space Vehicle Information + UBX_HNR_PVT = 0x00, // High rate Position, Velocity and Time + UBX_ID_UNK = 0xFF + } __attribute__((packed)); + + struct msg_hdr_t { + msg_class_t msg_class; + msg_id_t msg_id; + bool same_kind( const msg_hdr_t & msg ) const + { return (msg_class == msg.msg_class) && (msg_id == msg.msg_id); } + } __attribute__((packed)); + + struct msg_t : msg_hdr_t { + uint16_t length; // should be sizeof(this)-sizeof(msg_hdr_t) + #define UBX_MSG_LEN(msg) (sizeof(msg) - sizeof(ublox::msg_t)) + + msg_t() + { + length = 0; + }; + msg_t( enum msg_class_t m, enum msg_id_t i, uint16_t l = 0 ) + { + msg_class = m; + msg_id = i; + length = l; + } + void init() + { + uint8_t *mem = (uint8_t *) this; + memset( &mem[ sizeof(msg_t) ], 0, length ); + } + } __attribute__((packed)); + + /** + * Configure message intervals. + */ + + enum ubx_nmea_msg_t { // msg_id's for UBX_NMEA msg_class + UBX_GPGGA = 0x00, + UBX_GPGLL = 0x01, + UBX_GPGSA = 0x02, + UBX_GPGSV = 0x03, + UBX_GPRMC = 0x04, + UBX_GPVTG = 0x05, + UBX_GPGST = 0x07, + UBX_GPZDA = 0x08 + } __attribute__((packed)); + + struct cfg_msg_t : msg_t { + msg_class_t cfg_msg_class; + msg_id_t cfg_msg; + uint8_t rate; + + cfg_msg_t( msg_class_t m, msg_id_t i, uint8_t r ) + : msg_t( UBX_CFG, UBX_CFG_MSG, UBX_MSG_LEN(*this) ) + { + cfg_msg_class = m; + cfg_msg = i; + rate = r; + }; + } __attribute__((packed)); + + extern bool configNMEA( ubloxGPS &gps, NMEAGPS::nmea_msg_t msgType, uint8_t rate ); + + // Reset command + struct cfg_reset_t : msg_t { + + struct bbr_section_t + { + bool ephermeris :1; + bool almanac :1; + bool health :1; + bool klobuchard :1; + bool position :1; + bool clock_drift :1; + bool osc_param :1; + bool utc_param :1; + bool rtc :1; + bool reserved1 :2; + bool sfdr_param :1; + bool sfdr_veh_mon_param :1; + bool tct_param :1; + bool reserved2 :1; + bool autonomous_orbit_param:1; + } __attribute__((packed)); + + enum reset_mode_t + { + HW_RESET = 0x00, + CONTROLLED_SW_RESET = 0x01, + CONTROLLED_SW_RESET_GPS_ONLY = 0x02, + HW_RESET_AFTER_SHUTDOWN = 0x04, + CONTROLLED_GPS_STOP = 0x08, + CONTROLLED_GPS_START = 0x09 + } __attribute__((packed)); + + bbr_section_t clear_bbr_section; + reset_mode_t reset_mode : 8; + uint8_t reserved : 8; + + cfg_reset_t() + : msg_t( UBX_CFG, UBX_CFG_RST, UBX_MSG_LEN(*this) ) + { init(); } + + } __attribute__((packed)); + + // Configure navigation rate + enum time_ref_t { + UBX_TIME_REF_UTC=0, + UBX_TIME_REF_GPS=1 + } __attribute__((packed)); + + struct cfg_rate_t : msg_t { + uint16_t GPS_meas_rate; + uint16_t nav_rate; + enum time_ref_t time_ref:16; + + cfg_rate_t( uint16_t gr, uint16_t nr, enum time_ref_t tr ) + : msg_t( UBX_CFG, UBX_CFG_RATE, UBX_MSG_LEN(*this) ) + { + GPS_meas_rate = gr; + nav_rate = nr; + time_ref = tr; + } + } __attribute__((packed)); + + // Navigation Engine Expert Settings + enum dyn_model_t { + UBX_DYN_MODEL_PORTABLE = 0, + UBX_DYN_MODEL_STATIONARY = 2, + UBX_DYN_MODEL_PEDESTRIAN = 3, + UBX_DYN_MODEL_AUTOMOTIVE = 4, + UBX_DYN_MODEL_SEA = 5, + UBX_DYN_MODEL_AIR_1G = 6, + UBX_DYN_MODEL_AIR_2G = 7, + UBX_DYN_MODEL_AIR_4G = 8 + } __attribute__((packed)); + + enum position_fix_t { + UBX_POS_FIX_2D_ONLY = 1, + UBX_POS_FIX_3D_ONLY = 2, + UBX_POS_FIX_AUTO = 3 + } __attribute__((packed)); + + struct cfg_nav5_t : msg_t { + struct parameter_mask_t { + bool dyn_model :1; + bool min_elev :1; + bool fix :1; + bool dr_limit :1; + bool pos_mask :1; + bool time_mask :1; + bool static_hold_thr :1; + bool dgps_timeout :1; + int _unused_ :8; + } __attribute__((packed)); + + union { + struct parameter_mask_t apply; + uint16_t apply_word; + } __attribute__((packed)); + + enum dyn_model_t dyn_model:8; + enum position_fix_t fix_mode:8; + int32_t fixed_alt; // m MSL x0.01 + uint32_t fixed_alt_variance; // m^2 x0.0001 + int8_t min_elev; // deg + uint8_t dr_limit; // s + uint16_t pos_dop_mask; // x0.1 + uint16_t time_dop_mask; // x0.1 + uint16_t pos_acc_mask; // m + uint16_t time_acc_mask; // m + uint8_t static_hold_thr; // cm/s + uint8_t dgps_timeout; // s + uint32_t always_zero_1; + uint32_t always_zero_2; + uint32_t always_zero_3; + + cfg_nav5_t() : msg_t( UBX_CFG, UBX_CFG_NAV5, UBX_MSG_LEN(*this) ) + { + apply_word = 0xFF00; + always_zero_1 = + always_zero_2 = + always_zero_3 = 0; + } + + } __attribute__((packed)); + + // Geodetic Position Solution + struct nav_posllh_t : msg_t { + uint32_t time_of_week; // mS + int32_t lon; // deg * 1e7 + int32_t lat; // deg * 1e7 + int32_t height_above_ellipsoid; // mm + int32_t height_MSL; // mm + uint32_t horiz_acc; // mm + uint32_t vert_acc; // mm + + nav_posllh_t() : msg_t( UBX_NAV, UBX_NAV_POSLLH, UBX_MSG_LEN(*this) ) {}; + } __attribute__((packed)); + + // Receiver Navigation Status + struct nav_status_t : msg_t { + uint32_t time_of_week; // mS + enum status_t { + NAV_STAT_NONE, + NAV_STAT_DR_ONLY, + NAV_STAT_2D, + NAV_STAT_3D, + NAV_STAT_GPS_DR, + NAV_STAT_TIME_ONLY + } __attribute__((packed)) + status; + + struct flags_t { + bool gps_fix:1; + bool diff_soln:1; + bool week:1; + bool time_of_week:1; + } __attribute__((packed)) + flags; + + static gps_fix::status_t to_status( enum gps_fix::status_t status, flags_t flags ) + { + if (!flags.gps_fix) + return gps_fix::STATUS_NONE; + if (flags.diff_soln) + return gps_fix::STATUS_DGPS; + return status; + } + + struct { + bool dgps_input:1; + bool _skip_:6; + bool map_matching:1; + } __attribute__((packed)) + fix_status; + + enum { + PSM_ACQUISITION, + PSM_TRACKING, + PSM_POWER_OPTIMIZED_TRACKING, + PSM_INACTIVE + } + power_safe:2; // FW > v7.01 + + uint32_t time_to_first_fix; // ms time tag + uint32_t uptime; // ms since startup/reset + + nav_status_t() : msg_t( UBX_NAV, UBX_NAV_STATUS, UBX_MSG_LEN(*this) ) {}; + } __attribute__((packed)); + + // Dilutions of Precision + struct nav_dop_t : msg_t { + uint32_t time_of_week; // mS + + uint16_t gdop; // Geometric + uint16_t pdop; // Position + uint16_t tdop; // Time + uint16_t vdop; // Vertical + uint16_t hdop; // Horizontal + uint16_t ndop; // Northing + uint16_t edop; // Easting + + nav_dop_t() : msg_t( UBX_NAV, UBX_NAV_DOP, UBX_MSG_LEN(*this) ) {}; + } __attribute__((packed)); + + // Odometer Solution (NEO-M8 only) + struct nav_odo_t : msg_t { + uint8_t version; + uint8_t reserved[3]; + uint32_t time_of_week; // mS + uint32_t distance; // m + uint32_t total_distance; // m + uint32_t distanceSTD; // m (1-sigma) + + nav_odo_t() : msg_t( UBX_NAV, UBX_NAV_ODO, UBX_MSG_LEN(*this) ) {}; + } __attribute__((packed)); + + // Reset Odometer (NEO-M8 only) + struct nav_resetodo_t : msg_t { + // no payload, it's just a command + + nav_resetodo_t() : msg_t( UBX_NAV, UBX_NAV_RESETODO, UBX_MSG_LEN(*this) ) {}; + } __attribute__((packed)); + + // Velocity Solution in North/East/Down + struct nav_velned_t : msg_t { + uint32_t time_of_week; // mS + int32_t vel_north; // cm/s + int32_t vel_east; // cm/s + int32_t vel_down; // cm/s + uint32_t speed_3D; // cm/s + uint32_t speed_2D; // cm/s + int32_t heading; // degrees * 1e5 + uint32_t speed_acc; // cm/s + uint32_t heading_acc; // degrees * 1e5 + + nav_velned_t() : msg_t( UBX_NAV, UBX_NAV_VELNED, UBX_MSG_LEN(*this) ) {}; + } __attribute__((packed)); + + // GPS Time Solution + struct nav_timegps_t : msg_t { + uint32_t time_of_week; // mS + int32_t fractional_ToW; // nS + int16_t week; + int8_t leap_seconds; // GPS-UTC + struct valid_t { + bool time_of_week:1; + bool week:1; + bool leap_seconds:1; + } __attribute__((packed)) + valid; + + nav_timegps_t() : msg_t( UBX_NAV, UBX_NAV_TIMEGPS, UBX_MSG_LEN(*this) ) {}; + } __attribute__((packed)); + + // UTC Time Solution + struct nav_timeutc_t : msg_t { + uint32_t time_of_week; // mS + uint32_t time_accuracy; // nS + int32_t fractional_ToW; // nS + uint16_t year; // 1999..2099 + uint8_t month; // 1..12 + uint8_t day; // 1..31 + uint8_t hour; // 0..23 + uint8_t minute; // 0..59 + uint8_t second; // 0..59 + struct valid_t { + bool time_of_week:1; + bool week_number:1; + bool UTC:1; + } __attribute__((packed)) + valid; + + nav_timeutc_t() : msg_t( UBX_NAV, UBX_NAV_TIMEUTC, UBX_MSG_LEN(*this) ) {}; + } __attribute__((packed)); + + // Space Vehicle Information + struct nav_svinfo_t : msg_t { + uint32_t time_of_week; // mS + uint8_t num_channels; + enum { ANTARIS_OR_4, UBLOX_5, UBLOX_6 } chipgen:8; + uint16_t reserved2; + struct sv_t { + uint8_t channel; // 255 = no channel + uint8_t id; // Satellite ID + bool used_for_nav:1; + bool diff_corr :1; // differential correction available + bool orbit_avail :1; // orbit info available + bool orbit_eph :1; // orbit info is ephemeris + bool unhealthy :1; // SV should not be used + bool orbit_alm :1; // orbit info is Almanac Plus + bool orbit_AOP :1; // orbit info is AssistNow Autonomous + bool smoothed :1; // Carrier smoothed pseudorange used + enum { + IDLE, + SEARCHING, + ACQUIRED, + UNUSABLE, + CODE_LOCK, + CODE_AND_CARRIER_LOCK_1, + CODE_AND_CARRIER_LOCK_2, + CODE_AND_CARRIER_LOCK_3 + } + quality:8; + uint8_t snr; // dbHz + uint8_t elevation; // degrees + uint16_t azimuth; // degrees + uint32_t pr_res; // pseudo range residual in cm + }; + + // Calculate the number of bytes required to hold the + // specified number of channels. + static uint16_t size_for( uint8_t channels ) + { return sizeof(nav_svinfo_t) + (uint16_t)channels * sizeof(sv_t); } + + // Initialze the msg_hdr for the specified number of channels + void init( uint8_t max_channels ) + { + msg_class = UBX_NAV; + msg_id = UBX_NAV_SVINFO; + length = size_for( max_channels ) - sizeof(ublox::msg_t); + } + + } __attribute__((packed)); + + // High Rate PVT + struct hnr_pvt_t : msg_t { + uint32_t time_of_week; // mS + uint16_t year; // 1999..2099 + uint8_t month; // 1..12 + uint8_t day; // 1..31 + uint8_t hour; // 0..23 + uint8_t minute; // 0..59 + uint8_t second; // 0..59 + struct valid_t { + bool date:1; + bool time:1; + bool fully_resolved:1; + } __attribute__((packed)) + valid; + int32_t fractional_ToW; // nS + + nav_status_t::status_t status; + + struct flags_t { + bool gps_fix:1; + bool diff_soln:1; + bool week:1; + bool time_of_week:1; + bool heading_valid:1; + } __attribute__((packed)) + flags; + + static gps_fix::status_t to_status( enum gps_fix::status_t status, flags_t flags ) + { + if (!flags.gps_fix) + return gps_fix::STATUS_NONE; + if (flags.diff_soln) + return gps_fix::STATUS_DGPS; + return status; + } + + uint16_t reserved1; + + int32_t lon; // deg * 1e7 + int32_t lat; // deg * 1e7 + int32_t height_above_ellipsoid; // mm + int32_t height_MSL; // mm + + int32_t speed_2D; // mm/s + int32_t speed_3D; // mm/s + int32_t heading_motion; // degrees * 1e5 + int32_t heading_vehicle; // degrees * 1e5 + + uint32_t horiz_acc; // mm + uint32_t vert_acc; // mm + uint32_t speed_acc; // mm/s + uint32_t heading_acc; // degrees * 1e5 + + uint32_t reserved4; + + hnr_pvt_t() : msg_t( UBX_HNR, UBX_HNR_PVT, UBX_MSG_LEN(*this) ) {}; + } __attribute__((packed)); + + struct cfg_nmea_t : msg_t { + bool always_output_pos :1; // invalid or failed + bool output_invalid_pos :1; + bool output_invalid_time:1; + bool output_invalid_date:1; + bool use_GPS_only :1; + bool output_heading :1; // even if frozen + bool __not_used__ :2; + enum { + NMEA_V_2_1 = 0x21, + NMEA_V_2_3 = 0x23, + NMEA_V_4_0 = 0x40, // Neo M8 family only + NMEA_V_4_1 = 0x41 // Neo M8 family only + } + nmea_version : 8; + enum { + SV_PER_TALKERID_UNLIMITED = 0, + SV_PER_TALKERID_8 = 8, + SV_PER_TALKERID_12 = 12, + SV_PER_TALKERID_16 = 16 + } + num_sats_per_talker_id : 8; + bool compatibility_mode:1; + bool considering_mode :1; + bool max_line_length_82:1; // Neo M8 family only + uint8_t __not_used_1__ :5; + + cfg_nmea_t() : msg_t( UBX_CFG, UBX_CFG_NMEA, UBX_MSG_LEN(*this) ) {}; + + } __attribute__((packed)); + + struct cfg_nmea_v1_t : cfg_nmea_t { + bool filter_gps :1; + bool filter_sbas :1; + uint8_t __not_used_2__:2; + bool filter_qzss :1; + bool filter_glonass:1; + bool filter_beidou :1; + uint32_t __not_used_3__:25; + + bool proprietary_sat_numbering; // for non-NMEA satellites + enum { + MAIN_TALKER_ID_COMPUTED, + MAIN_TALKER_ID_GP, + MAIN_TALKER_ID_GL, + MAIN_TALKER_ID_GN, + MAIN_TALKER_ID_GA, + MAIN_TALKER_ID_GB + } + main_talker_id : 8; + bool gsv_uses_main_talker_id; // false means COMPUTED + enum cfg_nmea_version_t { + CFG_NMEA_V_0, // length = 12 + CFG_NMEA_V_1 // length = 20 (default) + } + version : 8; + + // Remaining fields are CFG_NMEA_V_1 only! + char beidou_talker_id[2]; // NULs mean default + uint8_t __reserved__[6]; + + cfg_nmea_v1_t( cfg_nmea_version_t v = CFG_NMEA_V_1 ) + { + version = v; + if (version == CFG_NMEA_V_0) + length = 12; + else { + length = 20; + for (uint8_t i=0; i<8;) // fills 'reserved' too + beidou_talker_id[i++] = 0; + } + }; + + } __attribute__((packed)); + +}; + +#endif // NMEAGPS_DERIVED_TYPES enabled + +#endif \ No newline at end of file diff --git a/software/firmware/libraries/SBUS/README.md b/software/firmware/libraries/SBUS/README.md new file mode 100644 index 0000000..084b2bf --- /dev/null +++ b/software/firmware/libraries/SBUS/README.md @@ -0,0 +1,92 @@ +# SBUS +Library for communicating with SBUS receivers and servos using Teensy 3.x and Teensy LC devices. + +# Description +SBUS is a protocol for RC receivers to send commands to servos. Unlike PWM, SBUS uses a bus architecture where a single signal line can be connected up to 16 servos with each receiving a unique command. SBUS capable servos are required; each can be programmed with a unique address (Channel 0 - 15) using an SBUS servo programmer. Advantages of SBUS include the reduction of wiring clutter and ease of parsing commands from RC receivers. + +Much of the information gathered on the SBUS protocol comes from [Uwe Gartmann](https://developer.mbed.org/users/Digixx/notebook/futaba-s-bus-controlled-by-mbed/). Implementation of sending SBUS packet data to servos on Teensy devices was greatly aided by this discussion and feedback from [Paul Stroffregen](https://forum.pjrc.com/archive/index.php/t-23956.html). + +The SBUS protocol uses inverted serial logic with a baud rate of 100000, 8 data bits, even parity bit, and 2 stop bits. The SBUS packet is 25 bytes long consisting of: +* Byte[0]: SBUS Header, 0x0F +* Byte[1-22]: 16 servo channels, 11 bits per servo channel +* Byte[23]: + * Bit 7: digital channel 17 (0x80) + * Bit 6: digital channel 18 (0x40) + * Bit 5: frame lost (0x20) + * Bit 4: failsafe activated (0x10) + * Bit 0 - 3: n/a +* Byte[24]: SBUS End Byte, 0x00 + +A table mapping bytes[1-22] to servo channels is [included](https://github.com/bolderflight/SBUS/blob/master/docs/bit-mapping.pdf). + +This library has two basic modes of functionality: + +1. Reading and parsing SBUS packets. This is useful for using an SBUS capable receiver to receive commands from a RC transmitter and parse the SBUS packet for vehicle control (closed loop control laws, servo mapping, mode change commands) and logging. SBUS packet reading and parsing is available with raw count data and calibrated to a +/- 1.0 float. Additionally, lost frame and failsafe data is made available. +2. Writing SBUS packets. This is useful for commanding up to 16 SBUS capable servos from the Teensy device. + +This library has been tested using FrSky SBUS capable receivers (X8R and X4R) and FrSky SBUS capable servos (D25MA). Feedback from users, especially with other brand receivers and servos (i.e. Futaba), would be greatly appreciated. + +# Usage +This library uses the [hardware serial](https://www.pjrc.com/teensy/td_uart.html) for Teensy devices. Additionally, this library [**requires Teensyduino 1.30 or above**](https://www.pjrc.com/teensy/td_download.html). + +Simply clone or download and extract the zipped library into your Arduino/libraries folder. + +Bind your SBUS capable receiver to your transmitter. Setup your SBUS capable servos by programming each with a unique channel number. + +**SBUS(HardwareSerial& bus)** +A SBUS object should be declared, specifying the hardware serial port the SBUS receiver and servos are connected to. For example, the following code declares a SBUS object called *x8r* located on the Teensy hardware serial port 1: + +```C++ +SBUS x8r(Serial1); +``` + +**void begin()** +This should be called in your setup function. It initializes the serial communication between the Teensy and SBUS receiver and servos. + +```C++ +x8r.begin(); +``` + +**bool read(uint16_t* channels, uint8_t* failsafe, uint16_t* lostFrames)** +*read(uint16_t* channels, uint8_t* failsafe, uint16_t* lostFrames)* reads data from the SBUS receiver and parses the SBUS packet. When a complete packet is received, *read(uint16_t* channels, uint8_t* failsafe, uint16_t* lostFrames)* returns *true* and the *channels[0-15]*, *failsafe*, and *lost frames* data is available. Note that *lost frames* is a counter that increments once each time a lost frame flag is read in the SBUS packet. For example, placing the following code in the loop function will print the value of *channel 0* every time a valid SBUS packet is received. + +```C++ +uint16_t channels[16]; +uint8_t failSafe; +uint16_t lostFrames = 0; + +if(x8r.read(&channels[0], &failSafe, &lostFrames)){ + Serial.println(channels[0]); +} +``` + +**bool readCal(float* calChannels, uint8_t* failsafe, uint16_t* lostFrames)** +*readCal(float* calChannels, uint8_t* failsafe, uint16_t* lostFrames)* reads data from the SBUS receiver and parses the SBUS packet. The data from *channels[0-15]* is calibrated to a +/- 1.0 float value assuming a linear relationship based on the minimum and maximum value (172 and 1811 using FrSky set to 0-100%). When a complete packet is received, *readCal(float* calChannels, uint8_t* failsafe, uint16_t* lostFrames)* returns *true* and the *calChannels[0-15]*, *failsafe*, and *lost frames* data is available. Note that *lost frames* is a counter that increments once each time a lost frame flag is read in the SBUS packet. For example, placing the following code in the loop function will print the calibrated value of *channel 0* every time a valid SBUS packet is received. + +```C++ +float channels[16]; +uint8_t failSafe; +uint16_t lostFrames = 0; + +if(x8r.readCal(&channels[0], &failSafe, &lostFrames)){ + Serial.println(channels[0]); +} +``` + +**void write(uint16_t* channels)** +*write(uint16_t* channels)* writes the SBUS packet to SBUS capable servos given position commands from *channels[0-15]*. Note that this function simply creates and sends the SBUS packet, but does not handle timing (i.e. the time between sending subsequent SBUS packets). This timing must be handled by the calling function. For example, placing the following code in the loop function will create and send the SBUS packet to servos every time a valid SBUS packet is received. + +```C++ +uint16_t channels[16]; +uint8_t failSafe; +uint16_t lostFrames = 0; + +// look for a good SBUS packet from the receiver +if(x8r.read(&channels[0], &failSafe, &lostFrames)){ + // write the SBUS packet to SBUS compatible servos + x8r.write(&channels[0]); +} +``` + +# Wiring +Please refer to the [Teensy pinout diagrams](https://www.pjrc.com/teensy/pinout.html) for hardware serial port pin information. The SBUS capable receiver ground should be connected to the Teensy ground. The receiver power may be connected to the Teensy Vin or to an external 5V power source. Receiver signal should be connected to the Teensy RX pin on the specified hardware serial port. The SBUS capable servo ground should be connected to the Teensy ground. **Servo power must come from an external power source**; Vin is not likely capable of supplying the necessary current. Servo signal should be connected to the Teensy TX pin on the specified hardware serial port. diff --git a/software/firmware/libraries/SBUS/SBUS.cpp b/software/firmware/libraries/SBUS/SBUS.cpp new file mode 100644 index 0000000..91de349 --- /dev/null +++ b/software/firmware/libraries/SBUS/SBUS.cpp @@ -0,0 +1,249 @@ +/* +SBUS.cpp +Brian R Taylor +brian.taylor@bolderflight.com +2017-01-13 + +Copyright (c) 2016 Bolder Flight Systems + +Permission is hereby granted, free of charge, to any person obtaining a copy of this software +and associated documentation files (the "Software"), to deal in the Software without restriction, +including without limitation the rights to use, copy, modify, merge, publish, distribute, +sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all copies or +substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING +BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND +NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, +DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + +// Teensy 3.0 || Teensy 3.1/3.2 || Teensy 3.5 || Teensy 3.6 || Teensy LC +#if defined(__MK20DX128__) || defined(__MK20DX256__) || defined(__MK64FX512__) || \ + defined(__MK66FX1M0__) || defined(__MKL26Z64__) + +#include "Arduino.h" +#include "SBUS.h" + +#if defined(__MK20DX128__) || defined(__MK20DX256__) + // globals needed for emulating two stop bytes on Teensy 3.0 and 3.1/3.2 + IntervalTimer serialTimer; + HardwareSerial* SERIALPORT; + uint8_t PACKET[25]; + volatile int SENDINDEX; + void sendByte(); +#endif + +/* SBUS object, input the serial bus */ +SBUS::SBUS(HardwareSerial& bus){ + _bus = &bus; +} + +/* starts the serial communication */ +void SBUS::begin(){ + // initialize parsing state + _fpos = 0; + #if defined(__MK20DX128__) || defined(__MK20DX256__) // Teensy 3.0 || Teensy 3.1/3.2 + // begin the serial port for SBUS + _bus->begin(100000,SERIAL_8E1_RXINV_TXINV); + SERIALPORT = _bus; + #endif + + #if defined(__MK64FX512__) || defined(__MK66FX1M0__) || defined(__MKL26Z64__) // Teensy 3.5 || Teensy 3.6 || Teensy LC + // begin the serial port for SBUS + _bus->begin(100000,SERIAL_8E2_RXINV_TXINV); + #endif +} + +/* read the SBUS data and calibrate it to +/- 1 */ +bool SBUS::readCal(float* calChannels, uint8_t* failsafe, uint16_t* lostFrames){ + uint16_t channels[16]; + + // read the SBUS data + if(read(&channels[0],failsafe,lostFrames)){ + + // linear calibration + for(uint8_t i = 0; i < 16; i++){ + calChannels[i] = channels[i] * _sbusScale + _sbusBias; + } + + // return true on receiving a full packet + return true; + } + else{ + + // return false if a full packet is not received + return false; + } +} + +/* read the SBUS data */ +bool SBUS::read(uint16_t* channels, uint8_t* failsafe, uint16_t* lostFrames){ + + // parse the SBUS packet + if(parse()){ + + // 16 channels of 11 bit data + channels[0] = (int16_t) ((_payload[0] |_payload[1]<<8) & 0x07FF); + channels[1] = (int16_t) ((_payload[1]>>3 |_payload[2]<<5) & 0x07FF); + channels[2] = (int16_t) ((_payload[2]>>6 |_payload[3]<<2 |_payload[4]<<10) & 0x07FF); + channels[3] = (int16_t) ((_payload[4]>>1 |_payload[5]<<7) & 0x07FF); + channels[4] = (int16_t) ((_payload[5]>>4 |_payload[6]<<4) & 0x07FF); + channels[5] = (int16_t) ((_payload[6]>>7 |_payload[7]<<1 |_payload[8]<<9) & 0x07FF); + channels[6] = (int16_t) ((_payload[8]>>2 |_payload[9]<<6) & 0x07FF); + channels[7] = (int16_t) ((_payload[9]>>5 |_payload[10]<<3) & 0x07FF); + channels[8] = (int16_t) ((_payload[11] |_payload[12]<<8) & 0x07FF); + channels[9] = (int16_t) ((_payload[12]>>3|_payload[13]<<5) & 0x07FF); + channels[10] = (int16_t) ((_payload[13]>>6|_payload[14]<<2|_payload[15]<<10) & 0x07FF); + channels[11] = (int16_t) ((_payload[15]>>1|_payload[16]<<7) & 0x07FF); + channels[12] = (int16_t) ((_payload[16]>>4|_payload[17]<<4) & 0x07FF); + channels[13] = (int16_t) ((_payload[17]>>7|_payload[18]<<1|_payload[19]<<9) & 0x07FF); + channels[14] = (int16_t) ((_payload[19]>>2|_payload[20]<<6) & 0x07FF); + channels[15] = (int16_t) ((_payload[20]>>5|_payload[21]<<3) & 0x07FF); + + // count lost frames + if (_payload[22] & _sbusLostFrame) { + *lostFrames = *lostFrames + 1; + } + + // failsafe state + if (_payload[22] & _sbusFailSafe) { + *failsafe = 1; + } + else{ + *failsafe = 0; + } + + // return true on receiving a full packet + return true; + } + else{ + + // return false if a full packet is not received + return false; + } +} + +/* parse the SBUS data */ +bool SBUS::parse(){ + static elapsedMicros sbusTime = 0; + + if(sbusTime > SBUS_TIMEOUT){_fpos = 0;} + + // see if serial data is available + while(_bus->available() > 0){ + sbusTime = 0; + static uint8_t c; + static uint8_t b; + c = _bus->read(); + + // find the header + if(_fpos == 0){ + if((c == _sbusHeader)&&((b == _sbusFooter)||((b & 0x0F) == _sbus2Footer))){ + _fpos++; + } + else{ + _fpos = 0; + } + } + else{ + + // strip off the data + if((_fpos-1) < _payloadSize){ + _payload[_fpos-1] = c; + _fpos++; + } + + // check the end byte + if((_fpos-1) == _payloadSize){ + if((c == _sbusFooter)||((c & 0x0F) == _sbus2Footer)) { + _fpos = 0; + return true; + } + else{ + _fpos = 0; + return false; + } + } + } + b = c; + } + // return false if a partial packet + return false; +} + +/* write SBUS packets */ +void SBUS::write(uint16_t* channels){ + uint8_t packet[25]; + + /* assemble the SBUS packet */ + + // SBUS header + packet[0] = _sbusHeader; + + // 16 channels of 11 bit data + packet[1] = (uint8_t) ((channels[0] & 0x07FF)); + packet[2] = (uint8_t) ((channels[0] & 0x07FF)>>8 | (channels[1] & 0x07FF)<<3); + packet[3] = (uint8_t) ((channels[1] & 0x07FF)>>5 | (channels[2] & 0x07FF)<<6); + packet[4] = (uint8_t) ((channels[2] & 0x07FF)>>2); + packet[5] = (uint8_t) ((channels[2] & 0x07FF)>>10 | (channels[3] & 0x07FF)<<1); + packet[6] = (uint8_t) ((channels[3] & 0x07FF)>>7 | (channels[4] & 0x07FF)<<4); + packet[7] = (uint8_t) ((channels[4] & 0x07FF)>>4 | (channels[5] & 0x07FF)<<7); + packet[8] = (uint8_t) ((channels[5] & 0x07FF)>>1); + packet[9] = (uint8_t) ((channels[5] & 0x07FF)>>9 | (channels[6] & 0x07FF)<<2); + packet[10] = (uint8_t) ((channels[6] & 0x07FF)>>6 | (channels[7] & 0x07FF)<<5); + packet[11] = (uint8_t) ((channels[7] & 0x07FF)>>3); + packet[12] = (uint8_t) ((channels[8] & 0x07FF)); + packet[13] = (uint8_t) ((channels[8] & 0x07FF)>>8 | (channels[9] & 0x07FF)<<3); + packet[14] = (uint8_t) ((channels[9] & 0x07FF)>>5 | (channels[10] & 0x07FF)<<6); + packet[15] = (uint8_t) ((channels[10] & 0x07FF)>>2); + packet[16] = (uint8_t) ((channels[10] & 0x07FF)>>10 | (channels[11] & 0x07FF)<<1); + packet[17] = (uint8_t) ((channels[11] & 0x07FF)>>7 | (channels[12] & 0x07FF)<<4); + packet[18] = (uint8_t) ((channels[12] & 0x07FF)>>4 | (channels[13] & 0x07FF)<<7); + packet[19] = (uint8_t) ((channels[13] & 0x07FF)>>1); + packet[20] = (uint8_t) ((channels[13] & 0x07FF)>>9 | (channels[14] & 0x07FF)<<2); + packet[21] = (uint8_t) ((channels[14] & 0x07FF)>>6 | (channels[15] & 0x07FF)<<5); + packet[22] = (uint8_t) ((channels[15] & 0x07FF)>>3); + + // flags + packet[23] = 0x00; + + // footer + packet[24] = _sbusFooter; + + #if defined(__MK20DX128__) || defined(__MK20DX256__) // Teensy 3.0 || Teensy 3.1/3.2 + // use ISR to send byte at a time, + // 130 us between bytes to emulate 2 stop bits + noInterrupts(); + memcpy(&PACKET,&packet,sizeof(packet)); + interrupts(); + serialTimer.priority(255); + serialTimer.begin(sendByte,130); + #endif + + #if defined(__MK64FX512__) || defined(__MK66FX1M0__) || defined(__MKL26Z64__) // Teensy 3.5 || Teensy 3.6 || Teensy LC + // write packet + _bus->write(packet,25); + #endif +} + +// function to send byte at a time with +// ISR to emulate 2 stop bits on Teensy 3.0 and 3.1/3.2 +#if defined(__MK20DX128__) || defined(__MK20DX256__) // Teensy 3.0 || Teensy 3.1/3.2 + void sendByte(){ + if(SENDINDEX < 25) { + SERIALPORT->write(PACKET[SENDINDEX]); + SENDINDEX++; + } + else{ + serialTimer.end(); + SENDINDEX = 0; + } + } +#endif + +#endif diff --git a/software/firmware/libraries/SBUS/SBUS.h b/software/firmware/libraries/SBUS/SBUS.h new file mode 100644 index 0000000..61cfbfd --- /dev/null +++ b/software/firmware/libraries/SBUS/SBUS.h @@ -0,0 +1,54 @@ +/* +SBUS.h +Brian R Taylor +brian.taylor@bolderflight.com +2017-01-13 + +Copyright (c) 2016 Bolder Flight Systems + +Permission is hereby granted, free of charge, to any person obtaining a copy of this software +and associated documentation files (the "Software"), to deal in the Software without restriction, +including without limitation the rights to use, copy, modify, merge, publish, distribute, +sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all copies or +substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING +BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND +NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, +DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + +#ifndef SBUS_h +#define SBUS_h + +#include "Arduino.h" + +class SBUS{ + public: + SBUS(HardwareSerial& bus); + void begin(); + bool read(uint16_t* channels, uint8_t* failsafe, uint16_t* lostFrames); + bool readCal(float* calChannels, uint8_t* failsafe, uint16_t* lostFrames); + void write(uint16_t* channels); + private: + uint8_t _fpos; + const uint16_t SBUS_TIMEOUT = 10000; + const float _sbusScale = 0.00122025625f; + const float _sbusBias = -1.2098840f; + const uint8_t _sbusHeader = 0x0F; + const uint8_t _sbusFooter = 0x00; + const uint8_t _sbus2Footer = 0x04; + const uint8_t _sbusLostFrame = 0x04; + const uint8_t _sbusFailSafe = 0x08; + static const uint8_t _payloadSize = 24; + uint8_t _payload[_payloadSize]; + HardwareSerial* _bus; + + bool parse(); +}; + +#endif diff --git a/software/firmware/libraries/SBUS/docs/bit-mapping.ods b/software/firmware/libraries/SBUS/docs/bit-mapping.ods new file mode 100644 index 0000000..ab439a5 Binary files /dev/null and b/software/firmware/libraries/SBUS/docs/bit-mapping.ods differ diff --git a/software/firmware/libraries/SBUS/docs/bit-mapping.pdf b/software/firmware/libraries/SBUS/docs/bit-mapping.pdf new file mode 100644 index 0000000..1169795 Binary files /dev/null and b/software/firmware/libraries/SBUS/docs/bit-mapping.pdf differ diff --git a/software/firmware/libraries/SBUS/examples/AIN_SBUS_example/AIN_SBUS_example.ino b/software/firmware/libraries/SBUS/examples/AIN_SBUS_example/AIN_SBUS_example.ino new file mode 100644 index 0000000..7b699ff --- /dev/null +++ b/software/firmware/libraries/SBUS/examples/AIN_SBUS_example/AIN_SBUS_example.ino @@ -0,0 +1,82 @@ +/* +SBUS_example.ino +Brian R Taylor +brian.taylor@bolderflight.com +2017-01-13 + +Copyright (c) 2016 Bolder Flight Systems + +Permission is hereby granted, free of charge, to any person obtaining a copy of this software +and associated documentation files (the "Software"), to deal in the Software without restriction, +including without limitation the rights to use, copy, modify, merge, publish, distribute, +sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all copies or +substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING +BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND +NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, +DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + +// This example reads 10 analog inputs, linearly maps them to SBUS +// servo commands and sends the command to the servos. In this case +// an interrupt is used to control packet timing. + +#include +#include "SBUS.h" + +// a SBUS object, which is on Teensy hardware +// serial port 1 +SBUS x8r(Serial1); + +// analog read values, 16 bit counts +uint16_t ain[10]; + +void setup() { + + // serial to display the channel commands for debugging + Serial.begin(115200); + + // begin the SBUS communication + x8r.begin(); + + // setup the analog read resolution to 16 bits + analogReadResolution(16); + + // setup an interrupt to send packets every 9 ms + Timer1.initialize(9000); + Timer1.attachInterrupt(sendSBUS); +} + +void loop() { + +} + +/* reads analog inputs and sends an SBUS packet */ +void sendSBUS() { + float scaleFactor = 1639.0f / 65535.0f; + float bias = 172.0f; + uint16_t channels[16]; + + // read the analog inputs + for(uint8_t i = 14; i < 24; i++) { + ain[i-14] = analogRead(i); + } + + // linearly map the analog measurements (0-65535) + // to the SBUS commands (172-1811) + for(uint8_t i = 0; i < 10; i++) { + channels[i] = (uint16_t)(((float)ain[i]) * scaleFactor + bias); + Serial.print(channels[i]); // print the channel command (172-1811) + Serial.print("\t"); + } + Serial.println(); + + // write the SBUS packet to an SBUS compatible servo + x8r.write(&channels[0]); +} + diff --git a/software/firmware/libraries/SBUS/examples/SBUS_example/SBUS_example.ino b/software/firmware/libraries/SBUS/examples/SBUS_example/SBUS_example.ino new file mode 100644 index 0000000..f24886a --- /dev/null +++ b/software/firmware/libraries/SBUS/examples/SBUS_example/SBUS_example.ino @@ -0,0 +1,61 @@ +/* +SBUS_example.ino +Brian R Taylor +brian.taylor@bolderflight.com +2016-09-21 + +Copyright (c) 2016 Bolder Flight Systems + +Permission is hereby granted, free of charge, to any person obtaining a copy of this software +and associated documentation files (the "Software"), to deal in the Software without restriction, +including without limitation the rights to use, copy, modify, merge, publish, distribute, +sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all copies or +substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING +BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND +NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, +DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + +// This example reads an SBUS packet from an +// SBUS receiver (FrSky X8R) and then takes that +// packet and writes it back to an SBUS +// compatible servo. The SBUS out capability (i.e. +// writing a command to the servo) could be generated +// independently; however, the packet timing would need +// to be controlled by the programmer, the write function +// simply generates an SBUS packet and writes it to the +// servos. In this case the packet timing is handled by the +// SBUS receiver and waiting for a good packet read. + +#include "SBUS.h" + +// a SBUS object, which is on Teensy hardware +// serial port 1 +SBUS x8r(Serial1); + +// channel, fail safe, and lost frames data +uint16_t channels[16]; +uint8_t failSafe; +uint16_t lostFrames = 0; + +void setup() { + // begin the SBUS communication + x8r.begin(); +} + +void loop() { + + // look for a good SBUS packet from the receiver + if(x8r.read(&channels[0], &failSafe, &lostFrames)){ + + // write the SBUS packet to an SBUS compatible servo + x8r.write(&channels[0]); + } +} + diff --git a/software/firmware/libraries/SBUS/keywords.txt b/software/firmware/libraries/SBUS/keywords.txt new file mode 100644 index 0000000..3e3c61e --- /dev/null +++ b/software/firmware/libraries/SBUS/keywords.txt @@ -0,0 +1,5 @@ +SBUS KEYWORD1 +begin KEYWORD2 +read KEYWORD2 +readCal KEYWORD2 +write KEYWORD2 diff --git a/software/firmware/libraries/modbus/Doxyfile b/software/firmware/libraries/modbus/Doxyfile new file mode 100644 index 0000000..8715223 --- /dev/null +++ b/software/firmware/libraries/modbus/Doxyfile @@ -0,0 +1,1921 @@ +# Doxyfile 1.8.4 + +# This file describes the settings to be used by the documentation system +# doxygen (www.doxygen.org) for a project +# +# All text after a hash (#) is considered a comment and will be ignored +# The format is: +# TAG = value [value, ...] +# For lists items can also be appended using: +# TAG += value [value, ...] +# Values that contain spaces should be placed between quotes (" ") + +#--------------------------------------------------------------------------- +# Project related configuration options +#--------------------------------------------------------------------------- + +# This tag specifies the encoding used for all characters in the config file +# that follow. The default is UTF-8 which is also the encoding used for all +# text before the first occurrence of this tag. Doxygen uses libiconv (or the +# iconv built into libc) for the transcoding. See +# http://www.gnu.org/software/libiconv for the list of possible encodings. + +DOXYFILE_ENCODING = UTF-8 + +# The PROJECT_NAME tag is a single word (or sequence of words) that should +# identify the project. Note that if you do not use Doxywizard you need +# to put quotes around the project name if it contains spaces. + +PROJECT_NAME = ModbusRtu + +# The PROJECT_NUMBER tag can be used to enter a project or revision number. +# This could be handy for archiving the generated documentation or +# if some version control system is used. + +PROJECT_NUMBER = 1.20 + +# Using the PROJECT_BRIEF tag one can provide an optional one line description +# for a project that appears at the top of each page and should give viewer +# a quick idea about the purpose of the project. Keep the description short. + +PROJECT_BRIEF = "Another Arduino library for communicating with Modbus devices over RS232/USB/485 via RTU protocol" + +# With the PROJECT_LOGO tag one can specify an logo or icon that is +# included in the documentation. The maximum height of the logo should not +# exceed 55 pixels and the maximum width should not exceed 200 pixels. +# Doxygen will copy the logo to the output directory. + +PROJECT_LOGO = + +# The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) +# base path where the generated documentation will be put. +# If a relative path is entered, it will be relative to the location +# where doxygen was started. If left blank the current directory will be used. + +OUTPUT_DIRECTORY = /home/samuel/Escriptori/libmodbus/documentation + +# If the CREATE_SUBDIRS tag is set to YES, then doxygen will create +# 4096 sub-directories (in 2 levels) under the output directory of each output +# format and will distribute the generated files over these directories. +# Enabling this option can be useful when feeding doxygen a huge amount of +# source files, where putting all generated files in the same directory would +# otherwise cause performance problems for the file system. + +CREATE_SUBDIRS = NO + +# The OUTPUT_LANGUAGE tag is used to specify the language in which all +# documentation generated by doxygen is written. Doxygen will use this +# information to generate all constant output in the proper language. +# The default language is English, other supported languages are: +# Afrikaans, Arabic, Brazilian, Catalan, Chinese, Chinese-Traditional, +# Croatian, Czech, Danish, Dutch, Esperanto, Farsi, Finnish, French, German, +# Greek, Hungarian, Italian, Japanese, Japanese-en (Japanese with English +# messages), Korean, Korean-en, Latvian, Lithuanian, Norwegian, Macedonian, +# Persian, Polish, Portuguese, Romanian, Russian, Serbian, Serbian-Cyrillic, +# Slovak, Slovene, Spanish, Swedish, Ukrainian, and Vietnamese. + +OUTPUT_LANGUAGE = English + +# If the BRIEF_MEMBER_DESC tag is set to YES (the default) Doxygen will +# include brief member descriptions after the members that are listed in +# the file and class documentation (similar to JavaDoc). +# Set to NO to disable this. + +BRIEF_MEMBER_DESC = YES + +# If the REPEAT_BRIEF tag is set to YES (the default) Doxygen will prepend +# the brief description of a member or function before the detailed description. +# Note: if both HIDE_UNDOC_MEMBERS and BRIEF_MEMBER_DESC are set to NO, the +# brief descriptions will be completely suppressed. + +REPEAT_BRIEF = YES + +# This tag implements a quasi-intelligent brief description abbreviator +# that is used to form the text in various listings. Each string +# in this list, if found as the leading text of the brief description, will be +# stripped from the text and the result after processing the whole list, is +# used as the annotated text. Otherwise, the brief description is used as-is. +# If left blank, the following values are used ("$name" is automatically +# replaced with the name of the entity): "The $name class" "The $name widget" +# "The $name file" "is" "provides" "specifies" "contains" +# "represents" "a" "an" "the" + +ABBREVIATE_BRIEF = "The $name class" \ + "The $name widget" \ + "The $name file" \ + is \ + provides \ + specifies \ + contains \ + represents \ + a \ + an \ + the + +# If the ALWAYS_DETAILED_SEC and REPEAT_BRIEF tags are both set to YES then +# Doxygen will generate a detailed section even if there is only a brief +# description. + +ALWAYS_DETAILED_SEC = NO + +# If the INLINE_INHERITED_MEMB tag is set to YES, doxygen will show all +# inherited members of a class in the documentation of that class as if those +# members were ordinary class members. Constructors, destructors and assignment +# operators of the base classes will not be shown. + +INLINE_INHERITED_MEMB = NO + +# If the FULL_PATH_NAMES tag is set to YES then Doxygen will prepend the full +# path before files name in the file list and in the header files. If set +# to NO the shortest path that makes the file name unique will be used. + +FULL_PATH_NAMES = YES + +# If the FULL_PATH_NAMES tag is set to YES then the STRIP_FROM_PATH tag +# can be used to strip a user-defined part of the path. Stripping is +# only done if one of the specified strings matches the left-hand part of +# the path. The tag can be used to show relative paths in the file list. +# If left blank the directory from which doxygen is run is used as the +# path to strip. Note that you specify absolute paths here, but also +# relative paths, which will be relative from the directory where doxygen is +# started. + +STRIP_FROM_PATH = + +# The STRIP_FROM_INC_PATH tag can be used to strip a user-defined part of +# the path mentioned in the documentation of a class, which tells +# the reader which header file to include in order to use a class. +# If left blank only the name of the header file containing the class +# definition is used. Otherwise one should specify the include paths that +# are normally passed to the compiler using the -I flag. + +STRIP_FROM_INC_PATH = + +# If the SHORT_NAMES tag is set to YES, doxygen will generate much shorter +# (but less readable) file names. This can be useful if your file system +# doesn't support long names like on DOS, Mac, or CD-ROM. + +SHORT_NAMES = NO + +# If the JAVADOC_AUTOBRIEF tag is set to YES then Doxygen +# will interpret the first line (until the first dot) of a JavaDoc-style +# comment as the brief description. If set to NO, the JavaDoc +# comments will behave just like regular Qt-style comments +# (thus requiring an explicit @brief command for a brief description.) + +JAVADOC_AUTOBRIEF = NO + +# If the QT_AUTOBRIEF tag is set to YES then Doxygen will +# interpret the first line (until the first dot) of a Qt-style +# comment as the brief description. If set to NO, the comments +# will behave just like regular Qt-style comments (thus requiring +# an explicit \brief command for a brief description.) + +QT_AUTOBRIEF = NO + +# The MULTILINE_CPP_IS_BRIEF tag can be set to YES to make Doxygen +# treat a multi-line C++ special comment block (i.e. a block of //! or /// +# comments) as a brief description. This used to be the default behaviour. +# The new default is to treat a multi-line C++ comment block as a detailed +# description. Set this tag to YES if you prefer the old behaviour instead. + +MULTILINE_CPP_IS_BRIEF = NO + +# If the INHERIT_DOCS tag is set to YES (the default) then an undocumented +# member inherits the documentation from any documented member that it +# re-implements. + +INHERIT_DOCS = YES + +# If the SEPARATE_MEMBER_PAGES tag is set to YES, then doxygen will produce +# a new page for each member. If set to NO, the documentation of a member will +# be part of the file/class/namespace that contains it. + +SEPARATE_MEMBER_PAGES = NO + +# The TAB_SIZE tag can be used to set the number of spaces in a tab. +# Doxygen uses this value to replace tabs by spaces in code fragments. + +TAB_SIZE = 4 + +# This tag can be used to specify a number of aliases that acts +# as commands in the documentation. An alias has the form "name=value". +# For example adding "sideeffect=\par Side Effects:\n" will allow you to +# put the command \sideeffect (or @sideeffect) in the documentation, which +# will result in a user-defined paragraph with heading "Side Effects:". +# You can put \n's in the value part of an alias to insert newlines. + +ALIASES = + +# This tag can be used to specify a number of word-keyword mappings (TCL only). +# A mapping has the form "name=value". For example adding +# "class=itcl::class" will allow you to use the command class in the +# itcl::class meaning. + +TCL_SUBST = + +# Set the OPTIMIZE_OUTPUT_FOR_C tag to YES if your project consists of C +# sources only. Doxygen will then generate output that is more tailored for C. +# For instance, some of the names that are used will be different. The list +# of all members will be omitted, etc. + +OPTIMIZE_OUTPUT_FOR_C = NO + +# Set the OPTIMIZE_OUTPUT_JAVA tag to YES if your project consists of Java +# sources only. Doxygen will then generate output that is more tailored for +# Java. For instance, namespaces will be presented as packages, qualified +# scopes will look different, etc. + +OPTIMIZE_OUTPUT_JAVA = NO + +# Set the OPTIMIZE_FOR_FORTRAN tag to YES if your project consists of Fortran +# sources only. Doxygen will then generate output that is more tailored for +# Fortran. + +OPTIMIZE_FOR_FORTRAN = NO + +# Set the OPTIMIZE_OUTPUT_VHDL tag to YES if your project consists of VHDL +# sources. Doxygen will then generate output that is tailored for +# VHDL. + +OPTIMIZE_OUTPUT_VHDL = NO + +# Doxygen selects the parser to use depending on the extension of the files it +# parses. With this tag you can assign which parser to use for a given +# extension. Doxygen has a built-in mapping, but you can override or extend it +# using this tag. The format is ext=language, where ext is a file extension, +# and language is one of the parsers supported by doxygen: IDL, Java, +# Javascript, CSharp, C, C++, D, PHP, Objective-C, Python, Fortran, VHDL, C, +# C++. For instance to make doxygen treat .inc files as Fortran files (default +# is PHP), and .f files as C (default is Fortran), use: inc=Fortran f=C. Note +# that for custom extensions you also need to set FILE_PATTERNS otherwise the +# files are not read by doxygen. + +EXTENSION_MAPPING = + +# If MARKDOWN_SUPPORT is enabled (the default) then doxygen pre-processes all +# comments according to the Markdown format, which allows for more readable +# documentation. See http://daringfireball.net/projects/markdown/ for details. +# The output of markdown processing is further processed by doxygen, so you +# can mix doxygen, HTML, and XML commands with Markdown formatting. +# Disable only in case of backward compatibilities issues. + +MARKDOWN_SUPPORT = YES + +# When enabled doxygen tries to link words that correspond to documented +# classes, or namespaces to their corresponding documentation. Such a link can +# be prevented in individual cases by by putting a % sign in front of the word +# or globally by setting AUTOLINK_SUPPORT to NO. + +AUTOLINK_SUPPORT = YES + +# If you use STL classes (i.e. std::string, std::vector, etc.) but do not want +# to include (a tag file for) the STL sources as input, then you should +# set this tag to YES in order to let doxygen match functions declarations and +# definitions whose arguments contain STL classes (e.g. func(std::string); v.s. +# func(std::string) {}). This also makes the inheritance and collaboration +# diagrams that involve STL classes more complete and accurate. + +BUILTIN_STL_SUPPORT = NO + +# If you use Microsoft's C++/CLI language, you should set this option to YES to +# enable parsing support. + +CPP_CLI_SUPPORT = NO + +# Set the SIP_SUPPORT tag to YES if your project consists of sip sources only. +# Doxygen will parse them like normal C++ but will assume all classes use public +# instead of private inheritance when no explicit protection keyword is present. + +SIP_SUPPORT = NO + +# For Microsoft's IDL there are propget and propput attributes to indicate +# getter and setter methods for a property. Setting this option to YES (the +# default) will make doxygen replace the get and set methods by a property in +# the documentation. This will only work if the methods are indeed getting or +# setting a simple type. If this is not the case, or you want to show the +# methods anyway, you should set this option to NO. + +IDL_PROPERTY_SUPPORT = YES + +# If member grouping is used in the documentation and the DISTRIBUTE_GROUP_DOC +# tag is set to YES, then doxygen will reuse the documentation of the first +# member in the group (if any) for the other members of the group. By default +# all members of a group must be documented explicitly. + +DISTRIBUTE_GROUP_DOC = NO + +# Set the SUBGROUPING tag to YES (the default) to allow class member groups of +# the same type (for instance a group of public functions) to be put as a +# subgroup of that type (e.g. under the Public Functions section). Set it to +# NO to prevent subgrouping. Alternatively, this can be done per class using +# the \nosubgrouping command. + +SUBGROUPING = YES + +# When the INLINE_GROUPED_CLASSES tag is set to YES, classes, structs and +# unions are shown inside the group in which they are included (e.g. using +# @ingroup) instead of on a separate page (for HTML and Man pages) or +# section (for LaTeX and RTF). + +INLINE_GROUPED_CLASSES = NO + +# When the INLINE_SIMPLE_STRUCTS tag is set to YES, structs, classes, and +# unions with only public data fields or simple typedef fields will be shown +# inline in the documentation of the scope in which they are defined (i.e. file, +# namespace, or group documentation), provided this scope is documented. If set +# to NO (the default), structs, classes, and unions are shown on a separate +# page (for HTML and Man pages) or section (for LaTeX and RTF). + +INLINE_SIMPLE_STRUCTS = NO + +# When TYPEDEF_HIDES_STRUCT is enabled, a typedef of a struct, union, or enum +# is documented as struct, union, or enum with the name of the typedef. So +# typedef struct TypeS {} TypeT, will appear in the documentation as a struct +# with name TypeT. When disabled the typedef will appear as a member of a file, +# namespace, or class. And the struct will be named TypeS. This can typically +# be useful for C code in case the coding convention dictates that all compound +# types are typedef'ed and only the typedef is referenced, never the tag name. + +TYPEDEF_HIDES_STRUCT = NO + +# The size of the symbol lookup cache can be set using LOOKUP_CACHE_SIZE. This +# cache is used to resolve symbols given their name and scope. Since this can +# be an expensive process and often the same symbol appear multiple times in +# the code, doxygen keeps a cache of pre-resolved symbols. If the cache is too +# small doxygen will become slower. If the cache is too large, memory is wasted. +# The cache size is given by this formula: 2^(16+LOOKUP_CACHE_SIZE). The valid +# range is 0..9, the default is 0, corresponding to a cache size of 2^16 = 65536 +# symbols. + +LOOKUP_CACHE_SIZE = 0 + +#--------------------------------------------------------------------------- +# Build related configuration options +#--------------------------------------------------------------------------- + +# If the EXTRACT_ALL tag is set to YES doxygen will assume all entities in +# documentation are documented, even if no documentation was available. +# Private class members and static file members will be hidden unless +# the EXTRACT_PRIVATE respectively EXTRACT_STATIC tags are set to YES + +EXTRACT_ALL = NO + +# If the EXTRACT_PRIVATE tag is set to YES all private members of a class +# will be included in the documentation. + +EXTRACT_PRIVATE = NO + +# If the EXTRACT_PACKAGE tag is set to YES all members with package or internal +# scope will be included in the documentation. + +EXTRACT_PACKAGE = NO + +# If the EXTRACT_STATIC tag is set to YES all static members of a file +# will be included in the documentation. + +EXTRACT_STATIC = NO + +# If the EXTRACT_LOCAL_CLASSES tag is set to YES classes (and structs) +# defined locally in source files will be included in the documentation. +# If set to NO only classes defined in header files are included. + +EXTRACT_LOCAL_CLASSES = YES + +# This flag is only useful for Objective-C code. When set to YES local +# methods, which are defined in the implementation section but not in +# the interface are included in the documentation. +# If set to NO (the default) only methods in the interface are included. + +EXTRACT_LOCAL_METHODS = NO + +# If this flag is set to YES, the members of anonymous namespaces will be +# extracted and appear in the documentation as a namespace called +# 'anonymous_namespace{file}', where file will be replaced with the base +# name of the file that contains the anonymous namespace. By default +# anonymous namespaces are hidden. + +EXTRACT_ANON_NSPACES = NO + +# If the HIDE_UNDOC_MEMBERS tag is set to YES, Doxygen will hide all +# undocumented members of documented classes, files or namespaces. +# If set to NO (the default) these members will be included in the +# various overviews, but no documentation section is generated. +# This option has no effect if EXTRACT_ALL is enabled. + +HIDE_UNDOC_MEMBERS = NO + +# If the HIDE_UNDOC_CLASSES tag is set to YES, Doxygen will hide all +# undocumented classes that are normally visible in the class hierarchy. +# If set to NO (the default) these classes will be included in the various +# overviews. This option has no effect if EXTRACT_ALL is enabled. + +HIDE_UNDOC_CLASSES = NO + +# If the HIDE_FRIEND_COMPOUNDS tag is set to YES, Doxygen will hide all +# friend (class|struct|union) declarations. +# If set to NO (the default) these declarations will be included in the +# documentation. + +HIDE_FRIEND_COMPOUNDS = NO + +# If the HIDE_IN_BODY_DOCS tag is set to YES, Doxygen will hide any +# documentation blocks found inside the body of a function. +# If set to NO (the default) these blocks will be appended to the +# function's detailed documentation block. + +HIDE_IN_BODY_DOCS = NO + +# The INTERNAL_DOCS tag determines if documentation +# that is typed after a \internal command is included. If the tag is set +# to NO (the default) then the documentation will be excluded. +# Set it to YES to include the internal documentation. + +INTERNAL_DOCS = NO + +# If the CASE_SENSE_NAMES tag is set to NO then Doxygen will only generate +# file names in lower-case letters. If set to YES upper-case letters are also +# allowed. This is useful if you have classes or files whose names only differ +# in case and if your file system supports case sensitive file names. Windows +# and Mac users are advised to set this option to NO. + +CASE_SENSE_NAMES = NO + +# If the HIDE_SCOPE_NAMES tag is set to NO (the default) then Doxygen +# will show members with their full class and namespace scopes in the +# documentation. If set to YES the scope will be hidden. + +HIDE_SCOPE_NAMES = NO + +# If the SHOW_INCLUDE_FILES tag is set to YES (the default) then Doxygen +# will put a list of the files that are included by a file in the documentation +# of that file. + +SHOW_INCLUDE_FILES = YES + +# If the FORCE_LOCAL_INCLUDES tag is set to YES then Doxygen +# will list include files with double quotes in the documentation +# rather than with sharp brackets. + +FORCE_LOCAL_INCLUDES = NO + +# If the INLINE_INFO tag is set to YES (the default) then a tag [inline] +# is inserted in the documentation for inline members. + +INLINE_INFO = YES + +# If the SORT_MEMBER_DOCS tag is set to YES (the default) then doxygen +# will sort the (detailed) documentation of file and class members +# alphabetically by member name. If set to NO the members will appear in +# declaration order. + +SORT_MEMBER_DOCS = YES + +# If the SORT_BRIEF_DOCS tag is set to YES then doxygen will sort the +# brief documentation of file, namespace and class members alphabetically +# by member name. If set to NO (the default) the members will appear in +# declaration order. + +SORT_BRIEF_DOCS = NO + +# If the SORT_MEMBERS_CTORS_1ST tag is set to YES then doxygen +# will sort the (brief and detailed) documentation of class members so that +# constructors and destructors are listed first. If set to NO (the default) +# the constructors will appear in the respective orders defined by +# SORT_MEMBER_DOCS and SORT_BRIEF_DOCS. +# This tag will be ignored for brief docs if SORT_BRIEF_DOCS is set to NO +# and ignored for detailed docs if SORT_MEMBER_DOCS is set to NO. + +SORT_MEMBERS_CTORS_1ST = NO + +# If the SORT_GROUP_NAMES tag is set to YES then doxygen will sort the +# hierarchy of group names into alphabetical order. If set to NO (the default) +# the group names will appear in their defined order. + +SORT_GROUP_NAMES = NO + +# If the SORT_BY_SCOPE_NAME tag is set to YES, the class list will be +# sorted by fully-qualified names, including namespaces. If set to +# NO (the default), the class list will be sorted only by class name, +# not including the namespace part. +# Note: This option is not very useful if HIDE_SCOPE_NAMES is set to YES. +# Note: This option applies only to the class list, not to the +# alphabetical list. + +SORT_BY_SCOPE_NAME = NO + +# If the STRICT_PROTO_MATCHING option is enabled and doxygen fails to +# do proper type resolution of all parameters of a function it will reject a +# match between the prototype and the implementation of a member function even +# if there is only one candidate or it is obvious which candidate to choose +# by doing a simple string match. By disabling STRICT_PROTO_MATCHING doxygen +# will still accept a match between prototype and implementation in such cases. + +STRICT_PROTO_MATCHING = NO + +# The GENERATE_TODOLIST tag can be used to enable (YES) or +# disable (NO) the todo list. This list is created by putting \todo +# commands in the documentation. + +GENERATE_TODOLIST = YES + +# The GENERATE_TESTLIST tag can be used to enable (YES) or +# disable (NO) the test list. This list is created by putting \test +# commands in the documentation. + +GENERATE_TESTLIST = YES + +# The GENERATE_BUGLIST tag can be used to enable (YES) or +# disable (NO) the bug list. This list is created by putting \bug +# commands in the documentation. + +GENERATE_BUGLIST = YES + +# The GENERATE_DEPRECATEDLIST tag can be used to enable (YES) or +# disable (NO) the deprecated list. This list is created by putting +# \deprecated commands in the documentation. + +GENERATE_DEPRECATEDLIST= YES + +# The ENABLED_SECTIONS tag can be used to enable conditional +# documentation sections, marked by \if section-label ... \endif +# and \cond section-label ... \endcond blocks. + +ENABLED_SECTIONS = + +# The MAX_INITIALIZER_LINES tag determines the maximum number of lines +# the initial value of a variable or macro consists of for it to appear in +# the documentation. If the initializer consists of more lines than specified +# here it will be hidden. Use a value of 0 to hide initializers completely. +# The appearance of the initializer of individual variables and macros in the +# documentation can be controlled using \showinitializer or \hideinitializer +# command in the documentation regardless of this setting. + +MAX_INITIALIZER_LINES = 30 + +# Set the SHOW_USED_FILES tag to NO to disable the list of files generated +# at the bottom of the documentation of classes and structs. If set to YES the +# list will mention the files that were used to generate the documentation. + +SHOW_USED_FILES = YES + +# Set the SHOW_FILES tag to NO to disable the generation of the Files page. +# This will remove the Files entry from the Quick Index and from the +# Folder Tree View (if specified). The default is YES. + +SHOW_FILES = YES + +# Set the SHOW_NAMESPACES tag to NO to disable the generation of the +# Namespaces page. This will remove the Namespaces entry from the Quick Index +# and from the Folder Tree View (if specified). The default is YES. + +SHOW_NAMESPACES = YES + +# The FILE_VERSION_FILTER tag can be used to specify a program or script that +# doxygen should invoke to get the current version for each file (typically from +# the version control system). Doxygen will invoke the program by executing (via +# popen()) the command , where is the value of +# the FILE_VERSION_FILTER tag, and is the name of an input file +# provided by doxygen. Whatever the program writes to standard output +# is used as the file version. See the manual for examples. + +FILE_VERSION_FILTER = + +# The LAYOUT_FILE tag can be used to specify a layout file which will be parsed +# by doxygen. The layout file controls the global structure of the generated +# output files in an output format independent way. To create the layout file +# that represents doxygen's defaults, run doxygen with the -l option. +# You can optionally specify a file name after the option, if omitted +# DoxygenLayout.xml will be used as the name of the layout file. + +LAYOUT_FILE = + +# The CITE_BIB_FILES tag can be used to specify one or more bib files +# containing the references data. This must be a list of .bib files. The +# .bib extension is automatically appended if omitted. Using this command +# requires the bibtex tool to be installed. See also +# http://en.wikipedia.org/wiki/BibTeX for more info. For LaTeX the style +# of the bibliography can be controlled using LATEX_BIB_STYLE. To use this +# feature you need bibtex and perl available in the search path. Do not use +# file names with spaces, bibtex cannot handle them. + +CITE_BIB_FILES = + +#--------------------------------------------------------------------------- +# configuration options related to warning and progress messages +#--------------------------------------------------------------------------- + +# The QUIET tag can be used to turn on/off the messages that are generated +# by doxygen. Possible values are YES and NO. If left blank NO is used. + +QUIET = NO + +# The WARNINGS tag can be used to turn on/off the warning messages that are +# generated by doxygen. Possible values are YES and NO. If left blank +# NO is used. + +WARNINGS = YES + +# If WARN_IF_UNDOCUMENTED is set to YES, then doxygen will generate warnings +# for undocumented members. If EXTRACT_ALL is set to YES then this flag will +# automatically be disabled. + +WARN_IF_UNDOCUMENTED = YES + +# If WARN_IF_DOC_ERROR is set to YES, doxygen will generate warnings for +# potential errors in the documentation, such as not documenting some +# parameters in a documented function, or documenting parameters that +# don't exist or using markup commands wrongly. + +WARN_IF_DOC_ERROR = YES + +# The WARN_NO_PARAMDOC option can be enabled to get warnings for +# functions that are documented, but have no documentation for their parameters +# or return value. If set to NO (the default) doxygen will only warn about +# wrong or incomplete parameter documentation, but not about the absence of +# documentation. + +WARN_NO_PARAMDOC = NO + +# The WARN_FORMAT tag determines the format of the warning messages that +# doxygen can produce. The string should contain the $file, $line, and $text +# tags, which will be replaced by the file and line number from which the +# warning originated and the warning text. Optionally the format may contain +# $version, which will be replaced by the version of the file (if it could +# be obtained via FILE_VERSION_FILTER) + +WARN_FORMAT = "$file:$line: $text" + +# The WARN_LOGFILE tag can be used to specify a file to which warning +# and error messages should be written. If left blank the output is written +# to stderr. + +WARN_LOGFILE = + +#--------------------------------------------------------------------------- +# configuration options related to the input files +#--------------------------------------------------------------------------- + +# The INPUT tag can be used to specify the files and/or directories that contain +# documented source files. You may enter file names like "myfile.cpp" or +# directories like "/usr/src/myproject". Separate the files or directories +# with spaces. + +INPUT = /home/samuel/Escriptori/libmodbus + +# This tag can be used to specify the character encoding of the source files +# that doxygen parses. Internally doxygen uses the UTF-8 encoding, which is +# also the default input encoding. Doxygen uses libiconv (or the iconv built +# into libc) for the transcoding. See http://www.gnu.org/software/libiconv for +# the list of possible encodings. + +INPUT_ENCODING = UTF-8 + +# If the value of the INPUT tag contains directories, you can use the +# FILE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp +# and *.h) to filter out the source-files in the directories. If left +# blank the following patterns are tested: +# *.c *.cc *.cxx *.cpp *.c++ *.d *.java *.ii *.ixx *.ipp *.i++ *.inl *.h *.hh +# *.hxx *.hpp *.h++ *.idl *.odl *.cs *.php *.php3 *.inc *.m *.mm *.dox *.py +# *.f90 *.f *.for *.vhd *.vhdl + +FILE_PATTERNS = *.c \ + *.cc \ + *.cxx \ + *.cpp \ + *.c++ \ + *.d \ + *.java \ + *.ii \ + *.ixx \ + *.ipp \ + *.i++ \ + *.inl \ + *.h \ + *.hh \ + *.hxx \ + *.hpp \ + *.h++ \ + *.idl \ + *.odl \ + *.cs \ + *.php \ + *.php3 \ + *.inc \ + *.m \ + *.markdown \ + *.md \ + *.mm \ + *.dox \ + *.py \ + *.f90 \ + *.f \ + *.for \ + *.vhd \ + *.vhdl + +# The RECURSIVE tag can be used to turn specify whether or not subdirectories +# should be searched for input files as well. Possible values are YES and NO. +# If left blank NO is used. + +RECURSIVE = NO + +# The EXCLUDE tag can be used to specify files and/or directories that should be +# excluded from the INPUT source files. This way you can easily exclude a +# subdirectory from a directory tree whose root is specified with the INPUT tag. +# Note that relative paths are relative to the directory from which doxygen is +# run. + +EXCLUDE = + +# The EXCLUDE_SYMLINKS tag can be used to select whether or not files or +# directories that are symbolic links (a Unix file system feature) are excluded +# from the input. + +EXCLUDE_SYMLINKS = NO + +# If the value of the INPUT tag contains directories, you can use the +# EXCLUDE_PATTERNS tag to specify one or more wildcard patterns to exclude +# certain files from those directories. Note that the wildcards are matched +# against the file with absolute path, so to exclude all test directories +# for example use the pattern */test/* + +EXCLUDE_PATTERNS = + +# The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names +# (namespaces, classes, functions, etc.) that should be excluded from the +# output. The symbol name can be a fully qualified name, a word, or if the +# wildcard * is used, a substring. Examples: ANamespace, AClass, +# AClass::ANamespace, ANamespace::*Test + +EXCLUDE_SYMBOLS = + +# The EXAMPLE_PATH tag can be used to specify one or more files or +# directories that contain example code fragments that are included (see +# the \include command). + +EXAMPLE_PATH = + +# If the value of the EXAMPLE_PATH tag contains directories, you can use the +# EXAMPLE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp +# and *.h) to filter out the source-files in the directories. If left +# blank all files are included. + +EXAMPLE_PATTERNS = * + +# If the EXAMPLE_RECURSIVE tag is set to YES then subdirectories will be +# searched for input files to be used with the \include or \dontinclude +# commands irrespective of the value of the RECURSIVE tag. +# Possible values are YES and NO. If left blank NO is used. + +EXAMPLE_RECURSIVE = NO + +# The IMAGE_PATH tag can be used to specify one or more files or +# directories that contain image that are included in the documentation (see +# the \image command). + +IMAGE_PATH = + +# The INPUT_FILTER tag can be used to specify a program that doxygen should +# invoke to filter for each input file. Doxygen will invoke the filter program +# by executing (via popen()) the command , where +# is the value of the INPUT_FILTER tag, and is the name of an +# input file. Doxygen will then use the output that the filter program writes +# to standard output. If FILTER_PATTERNS is specified, this tag will be ignored. +# Note that the filter must not add or remove lines; it is applied before the +# code is scanned, but not when the output code is generated. If lines are added +# or removed, the anchors will not be placed correctly. + +INPUT_FILTER = + +# The FILTER_PATTERNS tag can be used to specify filters on a per file pattern +# basis. Doxygen will compare the file name with each pattern and apply the +# filter if there is a match. The filters are a list of the form: +# pattern=filter (like *.cpp=my_cpp_filter). See INPUT_FILTER for further +# info on how filters are used. If FILTER_PATTERNS is empty or if +# non of the patterns match the file name, INPUT_FILTER is applied. + +FILTER_PATTERNS = + +# If the FILTER_SOURCE_FILES tag is set to YES, the input filter (if set using +# INPUT_FILTER) will be used to filter the input files when producing source +# files to browse (i.e. when SOURCE_BROWSER is set to YES). + +FILTER_SOURCE_FILES = NO + +# The FILTER_SOURCE_PATTERNS tag can be used to specify source filters per file +# pattern. A pattern will override the setting for FILTER_PATTERN (if any) +# and it is also possible to disable source filtering for a specific pattern +# using *.ext= (so without naming a filter). This option only has effect when +# FILTER_SOURCE_FILES is enabled. + +FILTER_SOURCE_PATTERNS = + +# If the USE_MD_FILE_AS_MAINPAGE tag refers to the name of a markdown file that +# is part of the input, its contents will be placed on the main page +# (index.html). This can be useful if you have a project on for instance GitHub +# and want reuse the introduction page also for the doxygen output. + +USE_MDFILE_AS_MAINPAGE = + +#--------------------------------------------------------------------------- +# configuration options related to source browsing +#--------------------------------------------------------------------------- + +# If the SOURCE_BROWSER tag is set to YES then a list of source files will +# be generated. Documented entities will be cross-referenced with these sources. +# Note: To get rid of all source code in the generated output, make sure also +# VERBATIM_HEADERS is set to NO. + +SOURCE_BROWSER = YES + +# Setting the INLINE_SOURCES tag to YES will include the body +# of functions and classes directly in the documentation. + +INLINE_SOURCES = NO + +# Setting the STRIP_CODE_COMMENTS tag to YES (the default) will instruct +# doxygen to hide any special comment blocks from generated source code +# fragments. Normal C, C++ and Fortran comments will always remain visible. + +STRIP_CODE_COMMENTS = YES + +# If the REFERENCED_BY_RELATION tag is set to YES +# then for each documented function all documented +# functions referencing it will be listed. + +REFERENCED_BY_RELATION = NO + +# If the REFERENCES_RELATION tag is set to YES +# then for each documented function all documented entities +# called/used by that function will be listed. + +REFERENCES_RELATION = NO + +# If the REFERENCES_LINK_SOURCE tag is set to YES (the default) +# and SOURCE_BROWSER tag is set to YES, then the hyperlinks from +# functions in REFERENCES_RELATION and REFERENCED_BY_RELATION lists will +# link to the source code. Otherwise they will link to the documentation. + +REFERENCES_LINK_SOURCE = YES + +# If the USE_HTAGS tag is set to YES then the references to source code +# will point to the HTML generated by the htags(1) tool instead of doxygen +# built-in source browser. The htags tool is part of GNU's global source +# tagging system (see http://www.gnu.org/software/global/global.html). You +# will need version 4.8.6 or higher. + +USE_HTAGS = NO + +# If the VERBATIM_HEADERS tag is set to YES (the default) then Doxygen +# will generate a verbatim copy of the header file for each class for +# which an include is specified. Set to NO to disable this. + +VERBATIM_HEADERS = YES + +#--------------------------------------------------------------------------- +# configuration options related to the alphabetical class index +#--------------------------------------------------------------------------- + +# If the ALPHABETICAL_INDEX tag is set to YES, an alphabetical index +# of all compounds will be generated. Enable this if the project +# contains a lot of classes, structs, unions or interfaces. + +ALPHABETICAL_INDEX = YES + +# If the alphabetical index is enabled (see ALPHABETICAL_INDEX) then +# the COLS_IN_ALPHA_INDEX tag can be used to specify the number of columns +# in which this list will be split (can be a number in the range [1..20]) + +COLS_IN_ALPHA_INDEX = 5 + +# In case all classes in a project start with a common prefix, all +# classes will be put under the same header in the alphabetical index. +# The IGNORE_PREFIX tag can be used to specify one or more prefixes that +# should be ignored while generating the index headers. + +IGNORE_PREFIX = + +#--------------------------------------------------------------------------- +# configuration options related to the HTML output +#--------------------------------------------------------------------------- + +# If the GENERATE_HTML tag is set to YES (the default) Doxygen will +# generate HTML output. + +GENERATE_HTML = YES + +# The HTML_OUTPUT tag is used to specify where the HTML docs will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `html' will be used as the default path. + +HTML_OUTPUT = html + +# The HTML_FILE_EXTENSION tag can be used to specify the file extension for +# each generated HTML page (for example: .htm,.php,.asp). If it is left blank +# doxygen will generate files with .html extension. + +HTML_FILE_EXTENSION = .html + +# The HTML_HEADER tag can be used to specify a personal HTML header for +# each generated HTML page. If it is left blank doxygen will generate a +# standard header. Note that when using a custom header you are responsible +# for the proper inclusion of any scripts and style sheets that doxygen +# needs, which is dependent on the configuration options used. +# It is advised to generate a default header using "doxygen -w html +# header.html footer.html stylesheet.css YourConfigFile" and then modify +# that header. Note that the header is subject to change so you typically +# have to redo this when upgrading to a newer version of doxygen or when +# changing the value of configuration settings such as GENERATE_TREEVIEW! + +HTML_HEADER = + +# The HTML_FOOTER tag can be used to specify a personal HTML footer for +# each generated HTML page. If it is left blank doxygen will generate a +# standard footer. + +HTML_FOOTER = + +# The HTML_STYLESHEET tag can be used to specify a user-defined cascading +# style sheet that is used by each HTML page. It can be used to +# fine-tune the look of the HTML output. If left blank doxygen will +# generate a default style sheet. Note that it is recommended to use +# HTML_EXTRA_STYLESHEET instead of this one, as it is more robust and this +# tag will in the future become obsolete. + +HTML_STYLESHEET = + +# The HTML_EXTRA_STYLESHEET tag can be used to specify an additional +# user-defined cascading style sheet that is included after the standard +# style sheets created by doxygen. Using this option one can overrule +# certain style aspects. This is preferred over using HTML_STYLESHEET +# since it does not replace the standard style sheet and is therefor more +# robust against future updates. Doxygen will copy the style sheet file to +# the output directory. + +HTML_EXTRA_STYLESHEET = + +# The HTML_EXTRA_FILES tag can be used to specify one or more extra images or +# other source files which should be copied to the HTML output directory. Note +# that these files will be copied to the base HTML output directory. Use the +# $relpath^ marker in the HTML_HEADER and/or HTML_FOOTER files to load these +# files. In the HTML_STYLESHEET file, use the file name only. Also note that +# the files will be copied as-is; there are no commands or markers available. + +HTML_EXTRA_FILES = + +# The HTML_COLORSTYLE_HUE tag controls the color of the HTML output. +# Doxygen will adjust the colors in the style sheet and background images +# according to this color. Hue is specified as an angle on a colorwheel, +# see http://en.wikipedia.org/wiki/Hue for more information. +# For instance the value 0 represents red, 60 is yellow, 120 is green, +# 180 is cyan, 240 is blue, 300 purple, and 360 is red again. +# The allowed range is 0 to 359. + +HTML_COLORSTYLE_HUE = 220 + +# The HTML_COLORSTYLE_SAT tag controls the purity (or saturation) of +# the colors in the HTML output. For a value of 0 the output will use +# grayscales only. A value of 255 will produce the most vivid colors. + +HTML_COLORSTYLE_SAT = 100 + +# The HTML_COLORSTYLE_GAMMA tag controls the gamma correction applied to +# the luminance component of the colors in the HTML output. Values below +# 100 gradually make the output lighter, whereas values above 100 make +# the output darker. The value divided by 100 is the actual gamma applied, +# so 80 represents a gamma of 0.8, The value 220 represents a gamma of 2.2, +# and 100 does not change the gamma. + +HTML_COLORSTYLE_GAMMA = 80 + +# If the HTML_TIMESTAMP tag is set to YES then the footer of each generated HTML +# page will contain the date and time when the page was generated. Setting +# this to NO can help when comparing the output of multiple runs. + +HTML_TIMESTAMP = YES + +# If the HTML_DYNAMIC_SECTIONS tag is set to YES then the generated HTML +# documentation will contain sections that can be hidden and shown after the +# page has loaded. + +HTML_DYNAMIC_SECTIONS = NO + +# With HTML_INDEX_NUM_ENTRIES one can control the preferred number of +# entries shown in the various tree structured indices initially; the user +# can expand and collapse entries dynamically later on. Doxygen will expand +# the tree to such a level that at most the specified number of entries are +# visible (unless a fully collapsed tree already exceeds this amount). +# So setting the number of entries 1 will produce a full collapsed tree by +# default. 0 is a special value representing an infinite number of entries +# and will result in a full expanded tree by default. + +HTML_INDEX_NUM_ENTRIES = 100 + +# If the GENERATE_DOCSET tag is set to YES, additional index files +# will be generated that can be used as input for Apple's Xcode 3 +# integrated development environment, introduced with OSX 10.5 (Leopard). +# To create a documentation set, doxygen will generate a Makefile in the +# HTML output directory. Running make will produce the docset in that +# directory and running "make install" will install the docset in +# ~/Library/Developer/Shared/Documentation/DocSets so that Xcode will find +# it at startup. +# See http://developer.apple.com/tools/creatingdocsetswithdoxygen.html +# for more information. + +GENERATE_DOCSET = NO + +# When GENERATE_DOCSET tag is set to YES, this tag determines the name of the +# feed. A documentation feed provides an umbrella under which multiple +# documentation sets from a single provider (such as a company or product suite) +# can be grouped. + +DOCSET_FEEDNAME = "Doxygen generated docs" + +# When GENERATE_DOCSET tag is set to YES, this tag specifies a string that +# should uniquely identify the documentation set bundle. This should be a +# reverse domain-name style string, e.g. com.mycompany.MyDocSet. Doxygen +# will append .docset to the name. + +DOCSET_BUNDLE_ID = org.doxygen.Project + +# When GENERATE_PUBLISHER_ID tag specifies a string that should uniquely +# identify the documentation publisher. This should be a reverse domain-name +# style string, e.g. com.mycompany.MyDocSet.documentation. + +DOCSET_PUBLISHER_ID = org.doxygen.Publisher + +# The GENERATE_PUBLISHER_NAME tag identifies the documentation publisher. + +DOCSET_PUBLISHER_NAME = Publisher + +# If the GENERATE_HTMLHELP tag is set to YES, additional index files +# will be generated that can be used as input for tools like the +# Microsoft HTML help workshop to generate a compiled HTML help file (.chm) +# of the generated HTML documentation. + +GENERATE_HTMLHELP = NO + +# If the GENERATE_HTMLHELP tag is set to YES, the CHM_FILE tag can +# be used to specify the file name of the resulting .chm file. You +# can add a path in front of the file if the result should not be +# written to the html output directory. + +CHM_FILE = + +# If the GENERATE_HTMLHELP tag is set to YES, the HHC_LOCATION tag can +# be used to specify the location (absolute path including file name) of +# the HTML help compiler (hhc.exe). If non-empty doxygen will try to run +# the HTML help compiler on the generated index.hhp. + +HHC_LOCATION = + +# If the GENERATE_HTMLHELP tag is set to YES, the GENERATE_CHI flag +# controls if a separate .chi index file is generated (YES) or that +# it should be included in the master .chm file (NO). + +GENERATE_CHI = NO + +# If the GENERATE_HTMLHELP tag is set to YES, the CHM_INDEX_ENCODING +# is used to encode HtmlHelp index (hhk), content (hhc) and project file +# content. + +CHM_INDEX_ENCODING = + +# If the GENERATE_HTMLHELP tag is set to YES, the BINARY_TOC flag +# controls whether a binary table of contents is generated (YES) or a +# normal table of contents (NO) in the .chm file. + +BINARY_TOC = NO + +# The TOC_EXPAND flag can be set to YES to add extra items for group members +# to the contents of the HTML help documentation and to the tree view. + +TOC_EXPAND = NO + +# If the GENERATE_QHP tag is set to YES and both QHP_NAMESPACE and +# QHP_VIRTUAL_FOLDER are set, an additional index file will be generated +# that can be used as input for Qt's qhelpgenerator to generate a +# Qt Compressed Help (.qch) of the generated HTML documentation. + +GENERATE_QHP = NO + +# If the QHG_LOCATION tag is specified, the QCH_FILE tag can +# be used to specify the file name of the resulting .qch file. +# The path specified is relative to the HTML output folder. + +QCH_FILE = + +# The QHP_NAMESPACE tag specifies the namespace to use when generating +# Qt Help Project output. For more information please see +# http://doc.trolltech.com/qthelpproject.html#namespace + +QHP_NAMESPACE = org.doxygen.Project + +# The QHP_VIRTUAL_FOLDER tag specifies the namespace to use when generating +# Qt Help Project output. For more information please see +# http://doc.trolltech.com/qthelpproject.html#virtual-folders + +QHP_VIRTUAL_FOLDER = doc + +# If QHP_CUST_FILTER_NAME is set, it specifies the name of a custom filter to +# add. For more information please see +# http://doc.trolltech.com/qthelpproject.html#custom-filters + +QHP_CUST_FILTER_NAME = + +# The QHP_CUST_FILT_ATTRS tag specifies the list of the attributes of the +# custom filter to add. For more information please see +# +# Qt Help Project / Custom Filters. + +QHP_CUST_FILTER_ATTRS = + +# The QHP_SECT_FILTER_ATTRS tag specifies the list of the attributes this +# project's +# filter section matches. +# +# Qt Help Project / Filter Attributes. + +QHP_SECT_FILTER_ATTRS = + +# If the GENERATE_QHP tag is set to YES, the QHG_LOCATION tag can +# be used to specify the location of Qt's qhelpgenerator. +# If non-empty doxygen will try to run qhelpgenerator on the generated +# .qhp file. + +QHG_LOCATION = + +# If the GENERATE_ECLIPSEHELP tag is set to YES, additional index files +# will be generated, which together with the HTML files, form an Eclipse help +# plugin. To install this plugin and make it available under the help contents +# menu in Eclipse, the contents of the directory containing the HTML and XML +# files needs to be copied into the plugins directory of eclipse. The name of +# the directory within the plugins directory should be the same as +# the ECLIPSE_DOC_ID value. After copying Eclipse needs to be restarted before +# the help appears. + +GENERATE_ECLIPSEHELP = NO + +# A unique identifier for the eclipse help plugin. When installing the plugin +# the directory name containing the HTML and XML files should also have +# this name. + +ECLIPSE_DOC_ID = org.doxygen.Project + +# The DISABLE_INDEX tag can be used to turn on/off the condensed index (tabs) +# at top of each HTML page. The value NO (the default) enables the index and +# the value YES disables it. Since the tabs have the same information as the +# navigation tree you can set this option to NO if you already set +# GENERATE_TREEVIEW to YES. + +DISABLE_INDEX = NO + +# The GENERATE_TREEVIEW tag is used to specify whether a tree-like index +# structure should be generated to display hierarchical information. +# If the tag value is set to YES, a side panel will be generated +# containing a tree-like index structure (just like the one that +# is generated for HTML Help). For this to work a browser that supports +# JavaScript, DHTML, CSS and frames is required (i.e. any modern browser). +# Windows users are probably better off using the HTML help feature. +# Since the tree basically has the same information as the tab index you +# could consider to set DISABLE_INDEX to NO when enabling this option. + +GENERATE_TREEVIEW = YES + +# The ENUM_VALUES_PER_LINE tag can be used to set the number of enum values +# (range [0,1..20]) that doxygen will group on one line in the generated HTML +# documentation. Note that a value of 0 will completely suppress the enum +# values from appearing in the overview section. + +ENUM_VALUES_PER_LINE = 4 + +# If the treeview is enabled (see GENERATE_TREEVIEW) then this tag can be +# used to set the initial width (in pixels) of the frame in which the tree +# is shown. + +TREEVIEW_WIDTH = 250 + +# When the EXT_LINKS_IN_WINDOW option is set to YES doxygen will open +# links to external symbols imported via tag files in a separate window. + +EXT_LINKS_IN_WINDOW = NO + +# Use this tag to change the font size of Latex formulas included +# as images in the HTML documentation. The default is 10. Note that +# when you change the font size after a successful doxygen run you need +# to manually remove any form_*.png images from the HTML output directory +# to force them to be regenerated. + +FORMULA_FONTSIZE = 10 + +# Use the FORMULA_TRANPARENT tag to determine whether or not the images +# generated for formulas are transparent PNGs. Transparent PNGs are +# not supported properly for IE 6.0, but are supported on all modern browsers. +# Note that when changing this option you need to delete any form_*.png files +# in the HTML output before the changes have effect. + +FORMULA_TRANSPARENT = YES + +# Enable the USE_MATHJAX option to render LaTeX formulas using MathJax +# (see http://www.mathjax.org) which uses client side Javascript for the +# rendering instead of using prerendered bitmaps. Use this if you do not +# have LaTeX installed or if you want to formulas look prettier in the HTML +# output. When enabled you may also need to install MathJax separately and +# configure the path to it using the MATHJAX_RELPATH option. + +USE_MATHJAX = NO + +# When MathJax is enabled you can set the default output format to be used for +# the MathJax output. Supported types are HTML-CSS, NativeMML (i.e. MathML) and +# SVG. The default value is HTML-CSS, which is slower, but has the best +# compatibility. + +MATHJAX_FORMAT = HTML-CSS + +# When MathJax is enabled you need to specify the location relative to the +# HTML output directory using the MATHJAX_RELPATH option. The destination +# directory should contain the MathJax.js script. For instance, if the mathjax +# directory is located at the same level as the HTML output directory, then +# MATHJAX_RELPATH should be ../mathjax. The default value points to +# the MathJax Content Delivery Network so you can quickly see the result without +# installing MathJax. However, it is strongly recommended to install a local +# copy of MathJax from http://www.mathjax.org before deployment. + +MATHJAX_RELPATH = http://cdn.mathjax.org/mathjax/latest + +# The MATHJAX_EXTENSIONS tag can be used to specify one or MathJax extension +# names that should be enabled during MathJax rendering. + +MATHJAX_EXTENSIONS = + +# The MATHJAX_CODEFILE tag can be used to specify a file with javascript +# pieces of code that will be used on startup of the MathJax code. + +MATHJAX_CODEFILE = + +# When the SEARCHENGINE tag is enabled doxygen will generate a search box +# for the HTML output. The underlying search engine uses javascript +# and DHTML and should work on any modern browser. Note that when using +# HTML help (GENERATE_HTMLHELP), Qt help (GENERATE_QHP), or docsets +# (GENERATE_DOCSET) there is already a search function so this one should +# typically be disabled. For large projects the javascript based search engine +# can be slow, then enabling SERVER_BASED_SEARCH may provide a better solution. + +SEARCHENGINE = YES + +# When the SERVER_BASED_SEARCH tag is enabled the search engine will be +# implemented using a web server instead of a web client using Javascript. +# There are two flavours of web server based search depending on the +# EXTERNAL_SEARCH setting. When disabled, doxygen will generate a PHP script for +# searching and an index file used by the script. When EXTERNAL_SEARCH is +# enabled the indexing and searching needs to be provided by external tools. +# See the manual for details. + +SERVER_BASED_SEARCH = NO + +# When EXTERNAL_SEARCH is enabled doxygen will no longer generate the PHP +# script for searching. Instead the search results are written to an XML file +# which needs to be processed by an external indexer. Doxygen will invoke an +# external search engine pointed to by the SEARCHENGINE_URL option to obtain +# the search results. Doxygen ships with an example indexer (doxyindexer) and +# search engine (doxysearch.cgi) which are based on the open source search +# engine library Xapian. See the manual for configuration details. + +EXTERNAL_SEARCH = NO + +# The SEARCHENGINE_URL should point to a search engine hosted by a web server +# which will returned the search results when EXTERNAL_SEARCH is enabled. +# Doxygen ships with an example search engine (doxysearch) which is based on +# the open source search engine library Xapian. See the manual for configuration +# details. + +SEARCHENGINE_URL = + +# When SERVER_BASED_SEARCH and EXTERNAL_SEARCH are both enabled the unindexed +# search data is written to a file for indexing by an external tool. With the +# SEARCHDATA_FILE tag the name of this file can be specified. + +SEARCHDATA_FILE = searchdata.xml + +# When SERVER_BASED_SEARCH AND EXTERNAL_SEARCH are both enabled the +# EXTERNAL_SEARCH_ID tag can be used as an identifier for the project. This is +# useful in combination with EXTRA_SEARCH_MAPPINGS to search through multiple +# projects and redirect the results back to the right project. + +EXTERNAL_SEARCH_ID = + +# The EXTRA_SEARCH_MAPPINGS tag can be used to enable searching through doxygen +# projects other than the one defined by this configuration file, but that are +# all added to the same external search index. Each project needs to have a +# unique id set via EXTERNAL_SEARCH_ID. The search mapping then maps the id +# of to a relative location where the documentation can be found. +# The format is: EXTRA_SEARCH_MAPPINGS = id1=loc1 id2=loc2 ... + +EXTRA_SEARCH_MAPPINGS = + +#--------------------------------------------------------------------------- +# configuration options related to the LaTeX output +#--------------------------------------------------------------------------- + +# If the GENERATE_LATEX tag is set to YES (the default) Doxygen will +# generate Latex output. + +GENERATE_LATEX = YES + +# The LATEX_OUTPUT tag is used to specify where the LaTeX docs will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `latex' will be used as the default path. + +LATEX_OUTPUT = latex + +# The LATEX_CMD_NAME tag can be used to specify the LaTeX command name to be +# invoked. If left blank `latex' will be used as the default command name. +# Note that when enabling USE_PDFLATEX this option is only used for +# generating bitmaps for formulas in the HTML output, but not in the +# Makefile that is written to the output directory. + +LATEX_CMD_NAME = latex + +# The MAKEINDEX_CMD_NAME tag can be used to specify the command name to +# generate index for LaTeX. If left blank `makeindex' will be used as the +# default command name. + +MAKEINDEX_CMD_NAME = makeindex + +# If the COMPACT_LATEX tag is set to YES Doxygen generates more compact +# LaTeX documents. This may be useful for small projects and may help to +# save some trees in general. + +COMPACT_LATEX = NO + +# The PAPER_TYPE tag can be used to set the paper type that is used +# by the printer. Possible values are: a4, letter, legal and +# executive. If left blank a4 will be used. + +PAPER_TYPE = a4 + +# The EXTRA_PACKAGES tag can be to specify one or more names of LaTeX +# packages that should be included in the LaTeX output. + +EXTRA_PACKAGES = + +# The LATEX_HEADER tag can be used to specify a personal LaTeX header for +# the generated latex document. The header should contain everything until +# the first chapter. If it is left blank doxygen will generate a +# standard header. Notice: only use this tag if you know what you are doing! + +LATEX_HEADER = + +# The LATEX_FOOTER tag can be used to specify a personal LaTeX footer for +# the generated latex document. The footer should contain everything after +# the last chapter. If it is left blank doxygen will generate a +# standard footer. Notice: only use this tag if you know what you are doing! + +LATEX_FOOTER = + +# The LATEX_EXTRA_FILES tag can be used to specify one or more extra images +# or other source files which should be copied to the LaTeX output directory. +# Note that the files will be copied as-is; there are no commands or markers +# available. + +LATEX_EXTRA_FILES = + +# If the PDF_HYPERLINKS tag is set to YES, the LaTeX that is generated +# is prepared for conversion to pdf (using ps2pdf). The pdf file will +# contain links (just like the HTML output) instead of page references +# This makes the output suitable for online browsing using a pdf viewer. + +PDF_HYPERLINKS = NO + +# If the USE_PDFLATEX tag is set to YES, pdflatex will be used instead of +# plain latex in the generated Makefile. Set this option to YES to get a +# higher quality PDF documentation. + +USE_PDFLATEX = YES + +# If the LATEX_BATCHMODE tag is set to YES, doxygen will add the \\batchmode. +# command to the generated LaTeX files. This will instruct LaTeX to keep +# running if errors occur, instead of asking the user for help. +# This option is also used when generating formulas in HTML. + +LATEX_BATCHMODE = NO + +# If LATEX_HIDE_INDICES is set to YES then doxygen will not +# include the index chapters (such as File Index, Compound Index, etc.) +# in the output. + +LATEX_HIDE_INDICES = NO + +# If LATEX_SOURCE_CODE is set to YES then doxygen will include +# source code with syntax highlighting in the LaTeX output. +# Note that which sources are shown also depends on other settings +# such as SOURCE_BROWSER. + +LATEX_SOURCE_CODE = NO + +# The LATEX_BIB_STYLE tag can be used to specify the style to use for the +# bibliography, e.g. plainnat, or ieeetr. The default style is "plain". See +# http://en.wikipedia.org/wiki/BibTeX for more info. + +LATEX_BIB_STYLE = plain + +#--------------------------------------------------------------------------- +# configuration options related to the RTF output +#--------------------------------------------------------------------------- + +# If the GENERATE_RTF tag is set to YES Doxygen will generate RTF output +# The RTF output is optimized for Word 97 and may not look very pretty with +# other RTF readers or editors. + +GENERATE_RTF = YES + +# The RTF_OUTPUT tag is used to specify where the RTF docs will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `rtf' will be used as the default path. + +RTF_OUTPUT = rtf + +# If the COMPACT_RTF tag is set to YES Doxygen generates more compact +# RTF documents. This may be useful for small projects and may help to +# save some trees in general. + +COMPACT_RTF = NO + +# If the RTF_HYPERLINKS tag is set to YES, the RTF that is generated +# will contain hyperlink fields. The RTF file will +# contain links (just like the HTML output) instead of page references. +# This makes the output suitable for online browsing using WORD or other +# programs which support those fields. +# Note: wordpad (write) and others do not support links. + +RTF_HYPERLINKS = NO + +# Load style sheet definitions from file. Syntax is similar to doxygen's +# config file, i.e. a series of assignments. You only have to provide +# replacements, missing definitions are set to their default value. + +RTF_STYLESHEET_FILE = + +# Set optional variables used in the generation of an rtf document. +# Syntax is similar to doxygen's config file. + +RTF_EXTENSIONS_FILE = + +#--------------------------------------------------------------------------- +# configuration options related to the man page output +#--------------------------------------------------------------------------- + +# If the GENERATE_MAN tag is set to YES (the default) Doxygen will +# generate man pages + +GENERATE_MAN = NO + +# The MAN_OUTPUT tag is used to specify where the man pages will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `man' will be used as the default path. + +MAN_OUTPUT = man + +# The MAN_EXTENSION tag determines the extension that is added to +# the generated man pages (default is the subroutine's section .3) + +MAN_EXTENSION = .3 + +# If the MAN_LINKS tag is set to YES and Doxygen generates man output, +# then it will generate one additional man file for each entity +# documented in the real man page(s). These additional files +# only source the real man page, but without them the man command +# would be unable to find the correct page. The default is NO. + +MAN_LINKS = NO + +#--------------------------------------------------------------------------- +# configuration options related to the XML output +#--------------------------------------------------------------------------- + +# If the GENERATE_XML tag is set to YES Doxygen will +# generate an XML file that captures the structure of +# the code including all documentation. + +GENERATE_XML = NO + +# The XML_OUTPUT tag is used to specify where the XML pages will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `xml' will be used as the default path. + +XML_OUTPUT = xml + +# The XML_SCHEMA tag can be used to specify an XML schema, +# which can be used by a validating XML parser to check the +# syntax of the XML files. + +XML_SCHEMA = + +# The XML_DTD tag can be used to specify an XML DTD, +# which can be used by a validating XML parser to check the +# syntax of the XML files. + +XML_DTD = + +# If the XML_PROGRAMLISTING tag is set to YES Doxygen will +# dump the program listings (including syntax highlighting +# and cross-referencing information) to the XML output. Note that +# enabling this will significantly increase the size of the XML output. + +XML_PROGRAMLISTING = YES + +#--------------------------------------------------------------------------- +# configuration options related to the DOCBOOK output +#--------------------------------------------------------------------------- + +# If the GENERATE_DOCBOOK tag is set to YES Doxygen will generate DOCBOOK files +# that can be used to generate PDF. + +GENERATE_DOCBOOK = NO + +# The DOCBOOK_OUTPUT tag is used to specify where the DOCBOOK pages will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be put in +# front of it. If left blank docbook will be used as the default path. + +DOCBOOK_OUTPUT = docbook + +#--------------------------------------------------------------------------- +# configuration options for the AutoGen Definitions output +#--------------------------------------------------------------------------- + +# If the GENERATE_AUTOGEN_DEF tag is set to YES Doxygen will +# generate an AutoGen Definitions (see autogen.sf.net) file +# that captures the structure of the code including all +# documentation. Note that this feature is still experimental +# and incomplete at the moment. + +GENERATE_AUTOGEN_DEF = NO + +#--------------------------------------------------------------------------- +# configuration options related to the Perl module output +#--------------------------------------------------------------------------- + +# If the GENERATE_PERLMOD tag is set to YES Doxygen will +# generate a Perl module file that captures the structure of +# the code including all documentation. Note that this +# feature is still experimental and incomplete at the +# moment. + +GENERATE_PERLMOD = NO + +# If the PERLMOD_LATEX tag is set to YES Doxygen will generate +# the necessary Makefile rules, Perl scripts and LaTeX code to be able +# to generate PDF and DVI output from the Perl module output. + +PERLMOD_LATEX = NO + +# If the PERLMOD_PRETTY tag is set to YES the Perl module output will be +# nicely formatted so it can be parsed by a human reader. This is useful +# if you want to understand what is going on. On the other hand, if this +# tag is set to NO the size of the Perl module output will be much smaller +# and Perl will parse it just the same. + +PERLMOD_PRETTY = YES + +# The names of the make variables in the generated doxyrules.make file +# are prefixed with the string contained in PERLMOD_MAKEVAR_PREFIX. +# This is useful so different doxyrules.make files included by the same +# Makefile don't overwrite each other's variables. + +PERLMOD_MAKEVAR_PREFIX = + +#--------------------------------------------------------------------------- +# Configuration options related to the preprocessor +#--------------------------------------------------------------------------- + +# If the ENABLE_PREPROCESSING tag is set to YES (the default) Doxygen will +# evaluate all C-preprocessor directives found in the sources and include +# files. + +ENABLE_PREPROCESSING = YES + +# If the MACRO_EXPANSION tag is set to YES Doxygen will expand all macro +# names in the source code. If set to NO (the default) only conditional +# compilation will be performed. Macro expansion can be done in a controlled +# way by setting EXPAND_ONLY_PREDEF to YES. + +MACRO_EXPANSION = NO + +# If the EXPAND_ONLY_PREDEF and MACRO_EXPANSION tags are both set to YES +# then the macro expansion is limited to the macros specified with the +# PREDEFINED and EXPAND_AS_DEFINED tags. + +EXPAND_ONLY_PREDEF = NO + +# If the SEARCH_INCLUDES tag is set to YES (the default) the includes files +# pointed to by INCLUDE_PATH will be searched when a #include is found. + +SEARCH_INCLUDES = YES + +# The INCLUDE_PATH tag can be used to specify one or more directories that +# contain include files that are not input files but should be processed by +# the preprocessor. + +INCLUDE_PATH = + +# You can use the INCLUDE_FILE_PATTERNS tag to specify one or more wildcard +# patterns (like *.h and *.hpp) to filter out the header-files in the +# directories. If left blank, the patterns specified with FILE_PATTERNS will +# be used. + +INCLUDE_FILE_PATTERNS = + +# The PREDEFINED tag can be used to specify one or more macro names that +# are defined before the preprocessor is started (similar to the -D option of +# gcc). The argument of the tag is a list of macros of the form: name +# or name=definition (no spaces). If the definition and the = are +# omitted =1 is assumed. To prevent a macro definition from being +# undefined via #undef or recursively expanded use the := operator +# instead of the = operator. + +PREDEFINED = + +# If the MACRO_EXPANSION and EXPAND_ONLY_PREDEF tags are set to YES then +# this tag can be used to specify a list of macro names that should be expanded. +# The macro definition that is found in the sources will be used. +# Use the PREDEFINED tag if you want to use a different macro definition that +# overrules the definition found in the source code. + +EXPAND_AS_DEFINED = + +# If the SKIP_FUNCTION_MACROS tag is set to YES (the default) then +# doxygen's preprocessor will remove all references to function-like macros +# that are alone on a line, have an all uppercase name, and do not end with a +# semicolon, because these will confuse the parser if not removed. + +SKIP_FUNCTION_MACROS = YES + +#--------------------------------------------------------------------------- +# Configuration::additions related to external references +#--------------------------------------------------------------------------- + +# The TAGFILES option can be used to specify one or more tagfiles. For each +# tag file the location of the external documentation should be added. The +# format of a tag file without this location is as follows: +# TAGFILES = file1 file2 ... +# Adding location for the tag files is done as follows: +# TAGFILES = file1=loc1 "file2 = loc2" ... +# where "loc1" and "loc2" can be relative or absolute paths +# or URLs. Note that each tag file must have a unique name (where the name does +# NOT include the path). If a tag file is not located in the directory in which +# doxygen is run, you must also specify the path to the tagfile here. + +TAGFILES = + +# When a file name is specified after GENERATE_TAGFILE, doxygen will create +# a tag file that is based on the input files it reads. + +GENERATE_TAGFILE = + +# If the ALLEXTERNALS tag is set to YES all external classes will be listed +# in the class index. If set to NO only the inherited external classes +# will be listed. + +ALLEXTERNALS = NO + +# If the EXTERNAL_GROUPS tag is set to YES all external groups will be listed +# in the modules index. If set to NO, only the current project's groups will +# be listed. + +EXTERNAL_GROUPS = YES + +# If the EXTERNAL_PAGES tag is set to YES all external pages will be listed +# in the related pages index. If set to NO, only the current project's +# pages will be listed. + +EXTERNAL_PAGES = YES + +# The PERL_PATH should be the absolute path and name of the perl script +# interpreter (i.e. the result of `which perl'). + +PERL_PATH = /usr/bin/perl + +#--------------------------------------------------------------------------- +# Configuration options related to the dot tool +#--------------------------------------------------------------------------- + +# If the CLASS_DIAGRAMS tag is set to YES (the default) Doxygen will +# generate a inheritance diagram (in HTML, RTF and LaTeX) for classes with base +# or super classes. Setting the tag to NO turns the diagrams off. Note that +# this option also works with HAVE_DOT disabled, but it is recommended to +# install and use dot, since it yields more powerful graphs. + +CLASS_DIAGRAMS = NO + +# You can define message sequence charts within doxygen comments using the \msc +# command. Doxygen will then run the mscgen tool (see +# http://www.mcternan.me.uk/mscgen/) to produce the chart and insert it in the +# documentation. The MSCGEN_PATH tag allows you to specify the directory where +# the mscgen tool resides. If left empty the tool is assumed to be found in the +# default search path. + +MSCGEN_PATH = + +# If set to YES, the inheritance and collaboration graphs will hide +# inheritance and usage relations if the target is undocumented +# or is not a class. + +HIDE_UNDOC_RELATIONS = YES + +# If you set the HAVE_DOT tag to YES then doxygen will assume the dot tool is +# available from the path. This tool is part of Graphviz, a graph visualization +# toolkit from AT&T and Lucent Bell Labs. The other options in this section +# have no effect if this option is set to NO (the default) + +HAVE_DOT = YES + +# The DOT_NUM_THREADS specifies the number of dot invocations doxygen is +# allowed to run in parallel. When set to 0 (the default) doxygen will +# base this on the number of processors available in the system. You can set it +# explicitly to a value larger than 0 to get control over the balance +# between CPU load and processing speed. + +DOT_NUM_THREADS = 0 + +# By default doxygen will use the Helvetica font for all dot files that +# doxygen generates. When you want a differently looking font you can specify +# the font name using DOT_FONTNAME. You need to make sure dot is able to find +# the font, which can be done by putting it in a standard location or by setting +# the DOTFONTPATH environment variable or by setting DOT_FONTPATH to the +# directory containing the font. + +DOT_FONTNAME = Helvetica + +# The DOT_FONTSIZE tag can be used to set the size of the font of dot graphs. +# The default size is 10pt. + +DOT_FONTSIZE = 10 + +# By default doxygen will tell dot to use the Helvetica font. +# If you specify a different font using DOT_FONTNAME you can use DOT_FONTPATH to +# set the path where dot can find it. + +DOT_FONTPATH = + +# If the CLASS_GRAPH and HAVE_DOT tags are set to YES then doxygen +# will generate a graph for each documented class showing the direct and +# indirect inheritance relations. Setting this tag to YES will force the +# CLASS_DIAGRAMS tag to NO. + +CLASS_GRAPH = YES + +# If the COLLABORATION_GRAPH and HAVE_DOT tags are set to YES then doxygen +# will generate a graph for each documented class showing the direct and +# indirect implementation dependencies (inheritance, containment, and +# class references variables) of the class with other documented classes. + +COLLABORATION_GRAPH = YES + +# If the GROUP_GRAPHS and HAVE_DOT tags are set to YES then doxygen +# will generate a graph for groups, showing the direct groups dependencies + +GROUP_GRAPHS = YES + +# If the UML_LOOK tag is set to YES doxygen will generate inheritance and +# collaboration diagrams in a style similar to the OMG's Unified Modeling +# Language. + +UML_LOOK = NO + +# If the UML_LOOK tag is enabled, the fields and methods are shown inside +# the class node. If there are many fields or methods and many nodes the +# graph may become too big to be useful. The UML_LIMIT_NUM_FIELDS +# threshold limits the number of items for each type to make the size more +# manageable. Set this to 0 for no limit. Note that the threshold may be +# exceeded by 50% before the limit is enforced. + +UML_LIMIT_NUM_FIELDS = 10 + +# If set to YES, the inheritance and collaboration graphs will show the +# relations between templates and their instances. + +TEMPLATE_RELATIONS = NO + +# If the ENABLE_PREPROCESSING, SEARCH_INCLUDES, INCLUDE_GRAPH, and HAVE_DOT +# tags are set to YES then doxygen will generate a graph for each documented +# file showing the direct and indirect include dependencies of the file with +# other documented files. + +INCLUDE_GRAPH = YES + +# If the ENABLE_PREPROCESSING, SEARCH_INCLUDES, INCLUDED_BY_GRAPH, and +# HAVE_DOT tags are set to YES then doxygen will generate a graph for each +# documented header file showing the documented files that directly or +# indirectly include this file. + +INCLUDED_BY_GRAPH = YES + +# If the CALL_GRAPH and HAVE_DOT options are set to YES then +# doxygen will generate a call dependency graph for every global function +# or class method. Note that enabling this option will significantly increase +# the time of a run. So in most cases it will be better to enable call graphs +# for selected functions only using the \callgraph command. + +CALL_GRAPH = YES + +# If the CALLER_GRAPH and HAVE_DOT tags are set to YES then +# doxygen will generate a caller dependency graph for every global function +# or class method. Note that enabling this option will significantly increase +# the time of a run. So in most cases it will be better to enable caller +# graphs for selected functions only using the \callergraph command. + +CALLER_GRAPH = YES + +# If the GRAPHICAL_HIERARCHY and HAVE_DOT tags are set to YES then doxygen +# will generate a graphical hierarchy of all classes instead of a textual one. + +GRAPHICAL_HIERARCHY = YES + +# If the DIRECTORY_GRAPH and HAVE_DOT tags are set to YES +# then doxygen will show the dependencies a directory has on other directories +# in a graphical way. The dependency relations are determined by the #include +# relations between the files in the directories. + +DIRECTORY_GRAPH = YES + +# The DOT_IMAGE_FORMAT tag can be used to set the image format of the images +# generated by dot. Possible values are svg, png, jpg, or gif. +# If left blank png will be used. If you choose svg you need to set +# HTML_FILE_EXTENSION to xhtml in order to make the SVG files +# visible in IE 9+ (other browsers do not have this requirement). + +DOT_IMAGE_FORMAT = png + +# If DOT_IMAGE_FORMAT is set to svg, then this option can be set to YES to +# enable generation of interactive SVG images that allow zooming and panning. +# Note that this requires a modern browser other than Internet Explorer. +# Tested and working are Firefox, Chrome, Safari, and Opera. For IE 9+ you +# need to set HTML_FILE_EXTENSION to xhtml in order to make the SVG files +# visible. Older versions of IE do not have SVG support. + +INTERACTIVE_SVG = NO + +# The tag DOT_PATH can be used to specify the path where the dot tool can be +# found. If left blank, it is assumed the dot tool can be found in the path. + +DOT_PATH = + +# The DOTFILE_DIRS tag can be used to specify one or more directories that +# contain dot files that are included in the documentation (see the +# \dotfile command). + +DOTFILE_DIRS = + +# The MSCFILE_DIRS tag can be used to specify one or more directories that +# contain msc files that are included in the documentation (see the +# \mscfile command). + +MSCFILE_DIRS = + +# The DOT_GRAPH_MAX_NODES tag can be used to set the maximum number of +# nodes that will be shown in the graph. If the number of nodes in a graph +# becomes larger than this value, doxygen will truncate the graph, which is +# visualized by representing a node as a red box. Note that doxygen if the +# number of direct children of the root node in a graph is already larger than +# DOT_GRAPH_MAX_NODES then the graph will not be shown at all. Also note +# that the size of a graph can be further restricted by MAX_DOT_GRAPH_DEPTH. + +DOT_GRAPH_MAX_NODES = 50 + +# The MAX_DOT_GRAPH_DEPTH tag can be used to set the maximum depth of the +# graphs generated by dot. A depth value of 3 means that only nodes reachable +# from the root by following a path via at most 3 edges will be shown. Nodes +# that lay further from the root node will be omitted. Note that setting this +# option to 1 or 2 may greatly reduce the computation time needed for large +# code bases. Also note that the size of a graph can be further restricted by +# DOT_GRAPH_MAX_NODES. Using a depth of 0 means no depth restriction. + +MAX_DOT_GRAPH_DEPTH = 0 + +# Set the DOT_TRANSPARENT tag to YES to generate images with a transparent +# background. This is disabled by default, because dot on Windows does not +# seem to support this out of the box. Warning: Depending on the platform used, +# enabling this option may lead to badly anti-aliased labels on the edges of +# a graph (i.e. they become hard to read). + +DOT_TRANSPARENT = NO + +# Set the DOT_MULTI_TARGETS tag to YES allow dot to generate multiple output +# files in one run (i.e. multiple -o and -T options on the command line). This +# makes dot run faster, but since only newer versions of dot (>1.8.10) +# support this, this feature is disabled by default. + +DOT_MULTI_TARGETS = NO + +# If the GENERATE_LEGEND tag is set to YES (the default) Doxygen will +# generate a legend page explaining the meaning of the various boxes and +# arrows in the dot generated graphs. + +GENERATE_LEGEND = YES + +# If the DOT_CLEANUP tag is set to YES (the default) Doxygen will +# remove the intermediate dot files that are used to generate +# the various graphs. + +DOT_CLEANUP = YES diff --git a/software/firmware/libraries/modbus/LICENSE.md b/software/firmware/libraries/modbus/LICENSE.md new file mode 100644 index 0000000..941668d --- /dev/null +++ b/software/firmware/libraries/modbus/LICENSE.md @@ -0,0 +1,458 @@ + + GNU LESSER GENERAL PUBLIC LICENSE + Version 2.1, February 1999 + + Copyright (C) 1991, 1999 Free Software Foundation, Inc. + 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + Everyone is permitted to copy and distribute verbatim copies + of this license document, but changing it is not allowed. + +[This is the first released version of the Lesser GPL. It also counts + as the successor of the GNU Library Public License, version 2, hence + the version number 2.1.] + + Preamble + + The licenses for most software are designed to take away your +freedom to share and change it. By contrast, the GNU General Public +Licenses are intended to guarantee your freedom to share and change +free software--to make sure the software is free for all its users. + + This license, the Lesser General Public License, applies to some +specially designated software packages--typically libraries--of the +Free Software Foundation and other authors who decide to use it. You +can use it too, but we suggest you first think carefully about whether +this license or the ordinary General Public License is the better +strategy to use in any particular case, based on the explanations below. + + When we speak of free software, we are referring to freedom of use, +not price. Our General Public Licenses are designed to make sure that +you have the freedom to distribute copies of free software (and charge +for this service if you wish); that you receive source code or can get +it if you want it; that you can change the software and use pieces of +it in new free programs; and that you are informed that you can do +these things. + + To protect your rights, we need to make restrictions that forbid +distributors to deny you these rights or to ask you to surrender these +rights. These restrictions translate to certain responsibilities for +you if you distribute copies of the library or if you modify it. + + For example, if you distribute copies of the library, whether gratis +or for a fee, you must give the recipients all the rights that we gave +you. You must make sure that they, too, receive or can get the source +code. If you link other code with the library, you must provide +complete object files to the recipients, so that they can relink them +with the library after making changes to the library and recompiling +it. And you must show them these terms so they know their rights. + + We protect your rights with a two-step method: (1) we copyright the +library, and (2) we offer you this license, which gives you legal +permission to copy, distribute and/or modify the library. + + To protect each distributor, we want to make it very clear that +there is no warranty for the free library. Also, if the library is +modified by someone else and passed on, the recipients should know +that what they have is not the original version, so that the original +author's reputation will not be affected by problems that might be +introduced by others. + + Finally, software patents pose a constant threat to the existence of +any free program. We wish to make sure that a company cannot +effectively restrict the users of a free program by obtaining a +restrictive license from a patent holder. Therefore, we insist that +any patent license obtained for a version of the library must be +consistent with the full freedom of use specified in this license. + + Most GNU software, including some libraries, is covered by the +ordinary GNU General Public License. This license, the GNU Lesser +General Public License, applies to certain designated libraries, and +is quite different from the ordinary General Public License. We use +this license for certain libraries in order to permit linking those +libraries into non-free programs. + + When a program is linked with a library, whether statically or using +a shared library, the combination of the two is legally speaking a +combined work, a derivative of the original library. The ordinary +General Public License therefore permits such linking only if the +entire combination fits its criteria of freedom. The Lesser General +Public License permits more lax criteria for linking other code with +the library. + + We call this license the "Lesser" General Public License because it +does Less to protect the user's freedom than the ordinary General +Public License. It also provides other free software developers Less +of an advantage over competing non-free programs. These disadvantages +are the reason we use the ordinary General Public License for many +libraries. However, the Lesser license provides advantages in certain +special circumstances. + + For example, on rare occasions, there may be a special need to +encourage the widest possible use of a certain library, so that it becomes +a de-facto standard. To achieve this, non-free programs must be +allowed to use the library. A more frequent case is that a free +library does the same job as widely used non-free libraries. In this +case, there is little to gain by limiting the free library to free +software only, so we use the Lesser General Public License. + + In other cases, permission to use a particular library in non-free +programs enables a greater number of people to use a large body of +free software. For example, permission to use the GNU C Library in +non-free programs enables many more people to use the whole GNU +operating system, as well as its variant, the GNU/Linux operating +system. + + Although the Lesser General Public License is Less protective of the +users' freedom, it does ensure that the user of a program that is +linked with the Library has the freedom and the wherewithal to run +that program using a modified version of the Library. + + The precise terms and conditions for copying, distribution and +modification follow. Pay close attention to the difference between a +"work based on the library" and a "work that uses the library". The +former contains code derived from the library, whereas the latter must +be combined with the library in order to run. + + GNU LESSER GENERAL PUBLIC LICENSE + TERMS AND CONDITIONS FOR COPYING, DISTRIBUTION AND MODIFICATION + + 0. This License Agreement applies to any software library or other +program which contains a notice placed by the copyright holder or +other authorized party saying it may be distributed under the terms of +this Lesser General Public License (also called "this License"). +Each licensee is addressed as "you". + + A "library" means a collection of software functions and/or data +prepared so as to be conveniently linked with application programs +(which use some of those functions and data) to form executables. + + The "Library", below, refers to any such software library or work +which has been distributed under these terms. A "work based on the +Library" means either the Library or any derivative work under +copyright law: that is to say, a work containing the Library or a +portion of it, either verbatim or with modifications and/or translated +straightforwardly into another language. (Hereinafter, translation is +included without limitation in the term "modification".) + + "Source code" for a work means the preferred form of the work for +making modifications to it. For a library, complete source code means +all the source code for all modules it contains, plus any associated +interface definition files, plus the scripts used to control compilation +and installation of the library. + + Activities other than copying, distribution and modification are not +covered by this License; they are outside its scope. The act of +running a program using the Library is not restricted, and output from +such a program is covered only if its contents constitute a work based +on the Library (independent of the use of the Library in a tool for +writing it). Whether that is true depends on what the Library does +and what the program that uses the Library does. + + 1. You may copy and distribute verbatim copies of the Library's +complete source code as you receive it, in any medium, provided that +you conspicuously and appropriately publish on each copy an +appropriate copyright notice and disclaimer of warranty; keep intact +all the notices that refer to this License and to the absence of any +warranty; and distribute a copy of this License along with the +Library. + + You may charge a fee for the physical act of transferring a copy, +and you may at your option offer warranty protection in exchange for a +fee. + + 2. You may modify your copy or copies of the Library or any portion +of it, thus forming a work based on the Library, and copy and +distribute such modifications or work under the terms of Section 1 +above, provided that you also meet all of these conditions: + + a) The modified work must itself be a software library. + + b) You must cause the files modified to carry prominent notices + stating that you changed the files and the date of any change. + + c) You must cause the whole of the work to be licensed at no + charge to all third parties under the terms of this License. + + d) If a facility in the modified Library refers to a function or a + table of data to be supplied by an application program that uses + the facility, other than as an argument passed when the facility + is invoked, then you must make a good faith effort to ensure that, + in the event an application does not supply such function or + table, the facility still operates, and performs whatever part of + its purpose remains meaningful. + + (For example, a function in a library to compute square roots has + a purpose that is entirely well-defined independent of the + application. Therefore, Subsection 2d requires that any + application-supplied function or table used by this function must + be optional: if the application does not supply it, the square + root function must still compute square roots.) + +These requirements apply to the modified work as a whole. If +identifiable sections of that work are not derived from the Library, +and can be reasonably considered independent and separate works in +themselves, then this License, and its terms, do not apply to those +sections when you distribute them as separate works. But when you +distribute the same sections as part of a whole which is a work based +on the Library, the distribution of the whole must be on the terms of +this License, whose permissions for other licensees extend to the +entire whole, and thus to each and every part regardless of who wrote +it. + +Thus, it is not the intent of this section to claim rights or contest +your rights to work written entirely by you; rather, the intent is to +exercise the right to control the distribution of derivative or +collective works based on the Library. + +In addition, mere aggregation of another work not based on the Library +with the Library (or with a work based on the Library) on a volume of +a storage or distribution medium does not bring the other work under +the scope of this License. + + 3. You may opt to apply the terms of the ordinary GNU General Public +License instead of this License to a given copy of the Library. To do +this, you must alter all the notices that refer to this License, so +that they refer to the ordinary GNU General Public License, version 2, +instead of to this License. (If a newer version than version 2 of the +ordinary GNU General Public License has appeared, then you can specify +that version instead if you wish.) Do not make any other change in +these notices. + + Once this change is made in a given copy, it is irreversible for +that copy, so the ordinary GNU General Public License applies to all +subsequent copies and derivative works made from that copy. + + This option is useful when you wish to copy part of the code of +the Library into a program that is not a library. + + 4. You may copy and distribute the Library (or a portion or +derivative of it, under Section 2) in object code or executable form +under the terms of Sections 1 and 2 above provided that you accompany +it with the complete corresponding machine-readable source code, which +must be distributed under the terms of Sections 1 and 2 above on a +medium customarily used for software interchange. + + If distribution of object code is made by offering access to copy +from a designated place, then offering equivalent access to copy the +source code from the same place satisfies the requirement to +distribute the source code, even though third parties are not +compelled to copy the source along with the object code. + + 5. A program that contains no derivative of any portion of the +Library, but is designed to work with the Library by being compiled or +linked with it, is called a "work that uses the Library". Such a +work, in isolation, is not a derivative work of the Library, and +therefore falls outside the scope of this License. + + However, linking a "work that uses the Library" with the Library +creates an executable that is a derivative of the Library (because it +contains portions of the Library), rather than a "work that uses the +library". The executable is therefore covered by this License. +Section 6 states terms for distribution of such executables. + + When a "work that uses the Library" uses material from a header file +that is part of the Library, the object code for the work may be a +derivative work of the Library even though the source code is not. +Whether this is true is especially significant if the work can be +linked without the Library, or if the work is itself a library. The +threshold for this to be true is not precisely defined by law. + + If such an object file uses only numerical parameters, data +structure layouts and accessors, and small macros and small inline +functions (ten lines or less in length), then the use of the object +file is unrestricted, regardless of whether it is legally a derivative +work. (Executables containing this object code plus portions of the +Library will still fall under Section 6.) + + Otherwise, if the work is a derivative of the Library, you may +distribute the object code for the work under the terms of Section 6. +Any executables containing that work also fall under Section 6, +whether or not they are linked directly with the Library itself. + + 6. As an exception to the Sections above, you may also combine or +link a "work that uses the Library" with the Library to produce a +work containing portions of the Library, and distribute that work +under terms of your choice, provided that the terms permit +modification of the work for the customer's own use and reverse +engineering for debugging such modifications. + + You must give prominent notice with each copy of the work that the +Library is used in it and that the Library and its use are covered by +this License. You must supply a copy of this License. If the work +during execution displays copyright notices, you must include the +copyright notice for the Library among them, as well as a reference +directing the user to the copy of this License. Also, you must do one +of these things: + + a) Accompany the work with the complete corresponding + machine-readable source code for the Library including whatever + changes were used in the work (which must be distributed under + Sections 1 and 2 above); and, if the work is an executable linked + with the Library, with the complete machine-readable "work that + uses the Library", as object code and/or source code, so that the + user can modify the Library and then relink to produce a modified + executable containing the modified Library. (It is understood + that the user who changes the contents of definitions files in the + Library will not necessarily be able to recompile the application + to use the modified definitions.) + + b) Use a suitable shared library mechanism for linking with the + Library. A suitable mechanism is one that (1) uses at run time a + copy of the library already present on the user's computer system, + rather than copying library functions into the executable, and (2) + will operate properly with a modified version of the library, if + the user installs one, as long as the modified version is + interface-compatible with the version that the work was made with. + + c) Accompany the work with a written offer, valid for at + least three years, to give the same user the materials + specified in Subsection 6a, above, for a charge no more + than the cost of performing this distribution. + + d) If distribution of the work is made by offering access to copy + from a designated place, offer equivalent access to copy the above + specified materials from the same place. + + e) Verify that the user has already received a copy of these + materials or that you have already sent this user a copy. + + For an executable, the required form of the "work that uses the +Library" must include any data and utility programs needed for +reproducing the executable from it. However, as a special exception, +the materials to be distributed need not include anything that is +normally distributed (in either source or binary form) with the major +components (compiler, kernel, and so on) of the operating system on +which the executable runs, unless that component itself accompanies +the executable. + + It may happen that this requirement contradicts the license +restrictions of other proprietary libraries that do not normally +accompany the operating system. Such a contradiction means you cannot +use both them and the Library together in an executable that you +distribute. + + 7. You may place library facilities that are a work based on the +Library side-by-side in a single library together with other library +facilities not covered by this License, and distribute such a combined +library, provided that the separate distribution of the work based on +the Library and of the other library facilities is otherwise +permitted, and provided that you do these two things: + + a) Accompany the combined library with a copy of the same work + based on the Library, uncombined with any other library + facilities. This must be distributed under the terms of the + Sections above. + + b) Give prominent notice with the combined library of the fact + that part of it is a work based on the Library, and explaining + where to find the accompanying uncombined form of the same work. + + 8. You may not copy, modify, sublicense, link with, or distribute +the Library except as expressly provided under this License. Any +attempt otherwise to copy, modify, sublicense, link with, or +distribute the Library is void, and will automatically terminate your +rights under this License. However, parties who have received copies, +or rights, from you under this License will not have their licenses +terminated so long as such parties remain in full compliance. + + 9. You are not required to accept this License, since you have not +signed it. However, nothing else grants you permission to modify or +distribute the Library or its derivative works. These actions are +prohibited by law if you do not accept this License. Therefore, by +modifying or distributing the Library (or any work based on the +Library), you indicate your acceptance of this License to do so, and +all its terms and conditions for copying, distributing or modifying +the Library or works based on it. + + 10. Each time you redistribute the Library (or any work based on the +Library), the recipient automatically receives a license from the +original licensor to copy, distribute, link with or modify the Library +subject to these terms and conditions. You may not impose any further +restrictions on the recipients' exercise of the rights granted herein. +You are not responsible for enforcing compliance by third parties with +this License. + + 11. If, as a consequence of a court judgment or allegation of patent +infringement or for any other reason (not limited to patent issues), +conditions are imposed on you (whether by court order, agreement or +otherwise) that contradict the conditions of this License, they do not +excuse you from the conditions of this License. If you cannot +distribute so as to satisfy simultaneously your obligations under this +License and any other pertinent obligations, then as a consequence you +may not distribute the Library at all. For example, if a patent +license would not permit royalty-free redistribution of the Library by +all those who receive copies directly or indirectly through you, then +the only way you could satisfy both it and this License would be to +refrain entirely from distribution of the Library. + +If any portion of this section is held invalid or unenforceable under any +particular circumstance, the balance of the section is intended to apply, +and the section as a whole is intended to apply in other circumstances. + +It is not the purpose of this section to induce you to infringe any +patents or other property right claims or to contest validity of any +such claims; this section has the sole purpose of protecting the +integrity of the free software distribution system which is +implemented by public license practices. Many people have made +generous contributions to the wide range of software distributed +through that system in reliance on consistent application of that +system; it is up to the author/donor to decide if he or she is willing +to distribute software through any other system and a licensee cannot +impose that choice. + +This section is intended to make thoroughly clear what is believed to +be a consequence of the rest of this License. + + 12. If the distribution and/or use of the Library is restricted in +certain countries either by patents or by copyrighted interfaces, the +original copyright holder who places the Library under this License may add +an explicit geographical distribution limitation excluding those countries, +so that distribution is permitted only in or among countries not thus +excluded. In such case, this License incorporates the limitation as if +written in the body of this License. + + 13. The Free Software Foundation may publish revised and/or new +versions of the Lesser General Public License from time to time. +Such new versions will be similar in spirit to the present version, +but may differ in detail to address new problems or concerns. + +Each version is given a distinguishing version number. If the Library +specifies a version number of this License which applies to it and +"any later version", you have the option of following the terms and +conditions either of that version or of any later version published by +the Free Software Foundation. If the Library does not specify a +license version number, you may choose any version ever published by +the Free Software Foundation. + + 14. If you wish to incorporate parts of the Library into other free +programs whose distribution conditions are incompatible with these, +write to the author to ask for permission. For software which is +copyrighted by the Free Software Foundation, write to the Free +Software Foundation; we sometimes make exceptions for this. Our +decision will be guided by the two goals of preserving the free status +of all derivatives of our free software and of promoting the sharing +and reuse of software generally. + + NO WARRANTY + + 15. BECAUSE THE LIBRARY IS LICENSED FREE OF CHARGE, THERE IS NO +WARRANTY FOR THE LIBRARY, TO THE EXTENT PERMITTED BY APPLICABLE LAW. +EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR +OTHER PARTIES PROVIDE THE LIBRARY "AS IS" WITHOUT WARRANTY OF ANY +KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR +PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE +LIBRARY IS WITH YOU. SHOULD THE LIBRARY PROVE DEFECTIVE, YOU ASSUME +THE COST OF ALL NECESSARY SERVICING, REPAIR OR CORRECTION. + + 16. IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN +WRITING WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MAY MODIFY +AND/OR REDISTRIBUTE THE LIBRARY AS PERMITTED ABOVE, BE LIABLE TO YOU +FOR DAMAGES, INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR +CONSEQUENTIAL DAMAGES ARISING OUT OF THE USE OR INABILITY TO USE THE +LIBRARY (INCLUDING BUT NOT LIMITED TO LOSS OF DATA OR DATA BEING +RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD PARTIES OR A +FAILURE OF THE LIBRARY TO OPERATE WITH ANY OTHER SOFTWARE), EVEN IF +SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH +DAMAGES. + diff --git a/software/firmware/libraries/modbus/ModbusRtu.h b/software/firmware/libraries/modbus/ModbusRtu.h new file mode 100644 index 0000000..693a3b2 --- /dev/null +++ b/software/firmware/libraries/modbus/ModbusRtu.h @@ -0,0 +1,1415 @@ +/** + * @file ModbusRtu.h + * @version 1.21 + * @date 2016.02.21 + * @author Samuel Marco i Armengol + * @contact sammarcoarmengol@gmail.com + * @contribution Helium6072 + * + * @description + * Arduino library for communicating with Modbus devices + * over RS232/USB/485 via RTU protocol. + * + * Further information: + * http://modbus.org/ + * http://modbus.org/docs/Modbus_over_serial_line_V1_02.pdf + * + * @license + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; version + * 2.1 of the License. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA + * + * @defgroup setup Modbus Object Instantiation/Initialization + * @defgroup loop Modbus Object Management + * @defgroup buffer Modbus Buffer Management + * @defgroup discrete Modbus Function Codes for Discrete Coils/Inputs + * @defgroup register Modbus Function Codes for Holding/Input Registers + * + */ + +#ifndef ModbusRtu_H_ +#define ModbusRtu_H_ + +#include +#include "Arduino.h" +#include "Print.h" +#include + +/** + * @struct modbus_t + * @brief + * Master query structure: + * This includes all the necessary fields to make the Master generate a Modbus query. + * A Master may keep several of these structures and send them cyclically or + * use them according to program needs. + */ +typedef struct +{ + uint8_t u8id; /*!< Slave address between 1 and 247. 0 means broadcast */ + uint8_t u8fct; /*!< Function code: 1, 2, 3, 4, 5, 6, 15 or 16 */ + uint16_t u16RegAdd; /*!< Address of the first register to access at slave/s */ + uint16_t u16CoilsNo; /*!< Number of coils or registers to access */ + uint16_t *au16reg; /*!< Pointer to memory image in master */ +} +modbus_t; + +enum +{ + RESPONSE_SIZE = 6, + EXCEPTION_SIZE = 3, + CHECKSUM_SIZE = 2 +}; + +/** + * @enum MESSAGE + * @brief + * Indexes to telegram frame positions + */ +enum MESSAGE +{ + ID = 0, //!< ID field + FUNC, //!< Function code position + ADD_HI, //!< Address high byte + ADD_LO, //!< Address low byte + NB_HI, //!< Number of coils or registers high byte + NB_LO, //!< Number of coils or registers low byte + BYTE_CNT //!< byte counter +}; + +/** + * @enum MB_FC + * @brief + * Modbus function codes summary. + * These are the implement function codes either for Master or for Slave. + * + * @see also fctsupported + * @see also modbus_t + */ +enum MB_FC +{ + MB_FC_NONE = 0, /*!< null operator */ + MB_FC_READ_COILS = 1, /*!< FCT=1 -> read coils or digital outputs */ + MB_FC_READ_DISCRETE_INPUT = 2, /*!< FCT=2 -> read digital inputs */ + MB_FC_READ_REGISTERS = 3, /*!< FCT=3 -> read registers or analog outputs */ + MB_FC_READ_INPUT_REGISTER = 4, /*!< FCT=4 -> read analog inputs */ + MB_FC_WRITE_COIL = 5, /*!< FCT=5 -> write single coil or output */ + MB_FC_WRITE_REGISTER = 6, /*!< FCT=6 -> write single register */ + MB_FC_WRITE_MULTIPLE_COILS = 15, /*!< FCT=15 -> write multiple coils or outputs */ + MB_FC_WRITE_MULTIPLE_REGISTERS = 16 /*!< FCT=16 -> write multiple registers */ +}; + +enum COM_STATES +{ + COM_IDLE = 0, + COM_WAITING = 1 + +}; + +enum ERR_LIST +{ + ERR_NOT_MASTER = -1, + ERR_POLLING = -2, + ERR_BUFF_OVERFLOW = -3, + ERR_BAD_CRC = -4, + ERR_EXCEPTION = -5 +}; + +enum +{ + NO_REPLY = 255, + EXC_FUNC_CODE = 1, + EXC_ADDR_RANGE = 2, + EXC_REGS_QUANT = 3, + EXC_EXECUTE = 4 +}; + +const unsigned char fctsupported[] = +{ + MB_FC_READ_COILS, + MB_FC_READ_DISCRETE_INPUT, + MB_FC_READ_REGISTERS, + MB_FC_READ_INPUT_REGISTER, + MB_FC_WRITE_COIL, + MB_FC_WRITE_REGISTER, + MB_FC_WRITE_MULTIPLE_COILS, + MB_FC_WRITE_MULTIPLE_REGISTERS +}; + +#define T35 5 +#define MAX_BUFFER 64 //!< maximum size for the communication buffer in bytes + +/** + * @class Modbus + * @brief + * Arduino class library for communicating with Modbus devices over + * USB/RS232/485 (via RTU protocol). + */ +class Modbus +{ +private: + HardwareSerial *port; //!< Pointer to Serial class object + SoftwareSerial *softPort; //!< Pointer to SoftwareSerial class object + uint8_t u8id; //!< 0=master, 1..247=slave number + uint8_t u8serno; //!< serial port: 0-Serial, 1..3-Serial1..Serial3; 4: use software serial + uint8_t u8txenpin; //!< flow control pin: 0=USB or RS-232 mode, >0=RS-485 mode + uint8_t u8state; + uint8_t u8lastError; + uint8_t au8Buffer[MAX_BUFFER]; + uint8_t u8BufferSize; + uint8_t u8lastRec; + uint16_t *au16regs; + uint16_t u16InCnt, u16OutCnt, u16errCnt; + uint16_t u16timeOut; + uint32_t u32time, u32timeOut; + uint8_t u8regsize; + + void init(uint8_t u8id, uint8_t u8serno, uint8_t u8txenpin); + void init(uint8_t u8id); + void sendTxBuffer(); + int8_t getRxBuffer(); + uint16_t calcCRC(uint8_t u8length); + uint8_t validateAnswer(); + uint8_t validateRequest(); + void get_FC1(); + void get_FC3(); + int8_t process_FC1( uint16_t *regs, uint8_t u8size ); + int8_t process_FC3( uint16_t *regs, uint8_t u8size ); + int8_t process_FC5( uint16_t *regs, uint8_t u8size ); + int8_t process_FC6( uint16_t *regs, uint8_t u8size ); + int8_t process_FC15( uint16_t *regs, uint8_t u8size ); + int8_t process_FC16( uint16_t *regs, uint8_t u8size ); + void buildException( uint8_t u8exception ); // build exception message + +public: + Modbus(); + Modbus(uint8_t u8id, uint8_t u8serno); + Modbus(uint8_t u8id, uint8_t u8serno, uint8_t u8txenpin); + Modbus(uint8_t u8id); + void begin(long u32speed); + void begin(SoftwareSerial *sPort, long u32speed); + void begin(long u32speed, uint8_t u8config); + void begin(); + void setTimeOut( uint16_t u16timeout); //!begin(u32speed); + if (u8txenpin > 1) // pin 0 & pin 1 are reserved for RX/TX + { + // return RS485 transceiver to transmit mode + pinMode(u8txenpin, OUTPUT); + digitalWrite(u8txenpin, LOW); +#if defined(TEENSYDUINO) + port->transmitterEnable(u8txenpin); +#endif + } + + while(port->read() >= 0); + u8lastRec = u8BufferSize = 0; + u16InCnt = u16OutCnt = u16errCnt = 0; +} + +/** + * @brief + * Initialize class object. + * + * Sets up the software serial port using specified baud rate and SoftwareSerial object. + * Call once class has been instantiated, typically within setup(). + * + * @param speed *softPort, pointer to SoftwareSerial class object + * @param speed baud rate, in standard increments (300..115200) + * @ingroup setup + */ +void Modbus::begin(SoftwareSerial *sPort, long u32speed) +{ + + softPort=sPort; + + softPort->begin(u32speed); + + if (u8txenpin > 1) // pin 0 & pin 1 are reserved for RX/TX + { + // return RS485 transceiver to transmit mode + pinMode(u8txenpin, OUTPUT); + digitalWrite(u8txenpin, LOW); + } + + while(softPort->read() >= 0); + u8lastRec = u8BufferSize = 0; + u16InCnt = u16OutCnt = u16errCnt = 0; +} + +/** + * @brief + * Initialize class object. + * + * Sets up the serial port using specified baud rate. + * Call once class has been instantiated, typically within setup(). + * + * @see http://arduino.cc/en/Serial/Begin#.Uy4CJ6aKlHY + * @param speed baud rate, in standard increments (300..115200) + * @param config data frame settings (data length, parity and stop bits) + * @ingroup setup + */ +void Modbus::begin(long u32speed,uint8_t u8config) +{ + + switch( u8serno ) + { + case 1: + port = &Serial1; + break; + case 2: + port = &Serial2; + break; + case 3: + port = &Serial3; + break; + case 0: + default: + break; + } + + port->begin(u32speed, u8config); + if (u8txenpin > 1) // pin 0 & pin 1 are reserved for RX/TX + { + // return RS485 transceiver to transmit mode + pinMode(u8txenpin, OUTPUT); + digitalWrite(u8txenpin, LOW); + } + + while(port->read() >= 0); + u8lastRec = u8BufferSize = 0; + u16InCnt = u16OutCnt = u16errCnt = 0; +} + +/** + * @brief + * Initialize default class object. + * + * Sets up the serial port using 19200 baud. + * Call once class has been instantiated, typically within setup(). + * + * @overload Modbus::begin(uint16_t u16BaudRate) + * @ingroup setup + */ +void Modbus::begin() +{ + begin(19200); +} + +/** + * @brief + * Method to write a new slave ID address + * + * @param u8id new slave address between 1 and 247 + * @ingroup setup + */ +void Modbus::setID( uint8_t u8id) +{ + if (( u8id != 0) && (u8id <= 247)) + { + this->u8id = u8id; + } +} + +/** + * @brief + * Method to read current slave ID address + * + * @return u8id current slave address between 1 and 247 + * @ingroup setup + */ +uint8_t Modbus::getID() +{ + return this->u8id; +} + +/** + * @brief + * Initialize time-out parameter + * + * Call once class has been instantiated, typically within setup(). + * The time-out timer is reset each time that there is a successful communication + * between Master and Slave. It works for both. + * + * @param time-out value (ms) + * @ingroup setup + */ +void Modbus::setTimeOut( uint16_t u16timeOut) +{ + this->u16timeOut = u16timeOut; +} + +/** + * @brief + * Return communication Watchdog state. + * It could be usefull to reset outputs if the watchdog is fired. + * + * @return TRUE if millis() > u32timeOut + * @ingroup loop + */ +boolean Modbus::getTimeOutState() +{ + return (millis() > u32timeOut); +} + +/** + * @brief + * Get input messages counter value + * This can be useful to diagnose communication + * + * @return input messages counter + * @ingroup buffer + */ +uint16_t Modbus::getInCnt() +{ + return u16InCnt; +} + +/** + * @brief + * Get transmitted messages counter value + * This can be useful to diagnose communication + * + * @return transmitted messages counter + * @ingroup buffer + */ +uint16_t Modbus::getOutCnt() +{ + return u16OutCnt; +} + +/** + * @brief + * Get errors counter value + * This can be useful to diagnose communication + * + * @return errors counter + * @ingroup buffer + */ +uint16_t Modbus::getErrCnt() +{ + return u16errCnt; +} + +/** + * Get modbus master state + * + * @return = 0 IDLE, = 1 WAITING FOR ANSWER + * @ingroup buffer + */ +uint8_t Modbus::getState() +{ + return u8state; +} + +/** + * Get the last error in the protocol processor + * + * @returnreturn NO_REPLY = 255 Time-out + * @return EXC_FUNC_CODE = 1 Function code not available + * @return EXC_ADDR_RANGE = 2 Address beyond available space for Modbus registers + * @return EXC_REGS_QUANT = 3 Coils or registers number beyond the available space + * @ingroup buffer + */ +uint8_t Modbus::getLastError() +{ + return u8lastError; +} + +/** + * @brief + * *** Only Modbus Master *** + * Generate a query to an slave with a modbus_t telegram structure + * The Master must be in COM_IDLE mode. After it, its state would be COM_WAITING. + * This method has to be called only in loop() section. + * + * @see modbus_t + * @param modbus_t modbus telegram structure (id, fct, ...) + * @ingroup loop + * @todo finish function 15 + */ +int8_t Modbus::query( modbus_t telegram ) +{ + uint8_t u8regsno, u8bytesno; + if (u8id!=0) return -2; + if (u8state != COM_IDLE) return -1; + + if ((telegram.u8id==0) || (telegram.u8id>247)) return -3; + + au16regs = telegram.au16reg; + + // telegram header + au8Buffer[ ID ] = telegram.u8id; + au8Buffer[ FUNC ] = telegram.u8fct; + au8Buffer[ ADD_HI ] = highByte(telegram.u16RegAdd ); + au8Buffer[ ADD_LO ] = lowByte( telegram.u16RegAdd ); + + switch( telegram.u8fct ) + { + case MB_FC_READ_COILS: + case MB_FC_READ_DISCRETE_INPUT: + case MB_FC_READ_REGISTERS: + case MB_FC_READ_INPUT_REGISTER: + au8Buffer[ NB_HI ] = highByte(telegram.u16CoilsNo ); + au8Buffer[ NB_LO ] = lowByte( telegram.u16CoilsNo ); + u8BufferSize = 6; + break; + case MB_FC_WRITE_COIL: + au8Buffer[ NB_HI ] = ((au16regs[0] > 0) ? 0xff : 0); + au8Buffer[ NB_LO ] = 0; + u8BufferSize = 6; + break; + case MB_FC_WRITE_REGISTER: + au8Buffer[ NB_HI ] = highByte(au16regs[0]); + au8Buffer[ NB_LO ] = lowByte(au16regs[0]); + u8BufferSize = 6; + break; + case MB_FC_WRITE_MULTIPLE_COILS: // TODO: implement "sending coils" + u8regsno = telegram.u16CoilsNo / 16; + u8bytesno = u8regsno * 2; + if ((telegram.u16CoilsNo % 16) != 0) + { + u8bytesno++; + u8regsno++; + } + + au8Buffer[ NB_HI ] = highByte(telegram.u16CoilsNo ); + au8Buffer[ NB_LO ] = lowByte( telegram.u16CoilsNo ); + au8Buffer[ NB_LO+1 ] = u8bytesno; + u8BufferSize = 7; + + u8regsno = u8bytesno = 0; // now auxiliary registers + for (uint16_t i = 0; i < telegram.u16CoilsNo; i++) + { + + + } + break; + + case MB_FC_WRITE_MULTIPLE_REGISTERS: + au8Buffer[ NB_HI ] = highByte(telegram.u16CoilsNo ); + au8Buffer[ NB_LO ] = lowByte( telegram.u16CoilsNo ); + au8Buffer[ NB_LO+1 ] = (uint8_t) ( telegram.u16CoilsNo * 2 ); + u8BufferSize = 7; + + for (uint16_t i=0; i< telegram.u16CoilsNo; i++) + { + au8Buffer[ u8BufferSize ] = highByte( au16regs[ i ] ); + u8BufferSize++; + au8Buffer[ u8BufferSize ] = lowByte( au16regs[ i ] ); + u8BufferSize++; + } + break; + } + + sendTxBuffer(); + u8state = COM_WAITING; + return 0; +} + +/** + * @brief *** Only for Modbus Master *** + * This method checks if there is any incoming answer if pending. + * If there is no answer, it would change Master state to COM_IDLE. + * This method must be called only at loop section. + * Avoid any delay() function. + * + * Any incoming data would be redirected to au16regs pointer, + * as defined in its modbus_t query telegram. + * + * @params nothing + * @return errors counter + * @ingroup loop + */ +int8_t Modbus::poll() +{ + // check if there is any incoming frame + uint8_t u8current; + if(u8serno<4) + u8current = port->available(); + else + u8current = softPort->available(); + + if (millis() > u32timeOut) + { + u8state = COM_IDLE; + u8lastError = NO_REPLY; + u16errCnt++; + return 0; + } + + if (u8current == 0) return 0; + + // check T35 after frame end or still no frame end + if (u8current != u8lastRec) + { + u8lastRec = u8current; + u32time = millis() + T35; + return 0; + } + if (millis() < u32time) return 0; + + // transfer Serial buffer frame to auBuffer + u8lastRec = 0; + int8_t i8state = getRxBuffer(); + if (i8state < 7) + { + u8state = COM_IDLE; + u16errCnt++; + return i8state; + } + + // validate message: id, CRC, FCT, exception + uint8_t u8exception = validateAnswer(); + if (u8exception != 0) + { + u8state = COM_IDLE; + return u8exception; + } + + // process answer + switch( au8Buffer[ FUNC ] ) + { + case MB_FC_READ_COILS: + case MB_FC_READ_DISCRETE_INPUT: + // call get_FC1 to transfer the incoming message to au16regs buffer + get_FC1( ); + break; + case MB_FC_READ_INPUT_REGISTER: + case MB_FC_READ_REGISTERS : + // call get_FC3 to transfer the incoming message to au16regs buffer + get_FC3( ); + break; + case MB_FC_WRITE_COIL: + case MB_FC_WRITE_REGISTER : + case MB_FC_WRITE_MULTIPLE_COILS: + case MB_FC_WRITE_MULTIPLE_REGISTERS : + // nothing to do + break; + default: + break; + } + u8state = COM_IDLE; + return u8BufferSize; +} + +/** + * @brief + * *** Only for Modbus Slave *** + * This method checks if there is any incoming query + * Afterwards, it would shoot a validation routine plus a register query + * Avoid any delay() function !!!! + * After a successful frame between the Master and the Slave, the time-out timer is reset. + * + * @param *regs register table for communication exchange + * @param u8size size of the register table + * @return 0 if no query, 1..4 if communication error, >4 if correct query processed + * @ingroup loop + */ +int8_t Modbus::poll( uint16_t *regs, uint8_t u8size ) +{ + + au16regs = regs; + u8regsize = u8size; + uint8_t u8current; + + + // check if there is any incoming frame + if(u8serno<4) + u8current = port->available(); + else + u8current = softPort->available(); + + if (u8current == 0) return 0; + + // check T35 after frame end or still no frame end + if (u8current != u8lastRec) + { + u8lastRec = u8current; + u32time = millis() + T35; + return 0; + } + if (millis() < u32time) return 0; + + u8lastRec = 0; + int8_t i8state = getRxBuffer(); + u8lastError = i8state; + if (i8state < 7) return i8state; + + // check slave id + if (au8Buffer[ ID ] != u8id) return 0; + + u32timeOut = millis() + long(u16timeOut); + u8lastError = 0; + + // validate message: CRC, FCT, address and size + uint8_t u8exception = validateRequest(); + if (u8exception > 0) + { + if (u8exception != NO_REPLY) + { + buildException( u8exception ); + sendTxBuffer(); + } + u8lastError = u8exception; + return u8exception; + } + + + + // process message + switch( au8Buffer[ FUNC ] ) + { + case MB_FC_READ_COILS: + case MB_FC_READ_DISCRETE_INPUT: + return process_FC1( regs, u8size ); + break; + case MB_FC_READ_INPUT_REGISTER: + case MB_FC_READ_REGISTERS : + return process_FC3( regs, u8size ); + break; + case MB_FC_WRITE_COIL: + return process_FC5( regs, u8size ); + break; + case MB_FC_WRITE_REGISTER : + return process_FC6( regs, u8size ); + break; + case MB_FC_WRITE_MULTIPLE_COILS: + return process_FC15( regs, u8size ); + break; + case MB_FC_WRITE_MULTIPLE_REGISTERS : + return process_FC16( regs, u8size ); + break; + default: + break; + } + + return i8state; +} + +/* _____PRIVATE FUNCTIONS_____________________________________________________ */ + +void Modbus::init(uint8_t u8id, uint8_t u8serno, uint8_t u8txenpin) +{ + this->u8id = u8id; + this->u8serno = (u8serno > 3) ? 0 : u8serno; + this->u8txenpin = u8txenpin; + this->u16timeOut = 1000; +} + +void Modbus::init(uint8_t u8id) +{ + this->u8id = u8id; + this->u8serno = 4; + this->u8txenpin = 0; + this->u16timeOut = 1000; +} + +/** + * @brief + * This method moves Serial buffer data to the Modbus au8Buffer. + * + * @return buffer size if OK, ERR_BUFF_OVERFLOW if u8BufferSize >= MAX_BUFFER + * @ingroup buffer + */ +int8_t Modbus::getRxBuffer() +{ + boolean bBuffOverflow = false; + + if (u8txenpin > 1) digitalWrite( u8txenpin, LOW ); + + u8BufferSize = 0; + if(u8serno<4) + while ( port->available() ) + { + au8Buffer[ u8BufferSize ] = port->read(); + u8BufferSize ++; + + if (u8BufferSize >= MAX_BUFFER) bBuffOverflow = true; + } + else + while ( softPort->available() ) + { + au8Buffer[ u8BufferSize ] = softPort->read(); + u8BufferSize ++; + + if (u8BufferSize >= MAX_BUFFER) bBuffOverflow = true; + } + u16InCnt++; + + if (bBuffOverflow) + { + u16errCnt++; + return ERR_BUFF_OVERFLOW; + } + return u8BufferSize; +} + +/** + * @brief + * This method transmits au8Buffer to Serial line. + * Only if u8txenpin != 0, there is a flow handling in order to keep + * the RS485 transceiver in output state as long as the message is being sent. + * This is done with UCSRxA register. + * The CRC is appended to the buffer before starting to send it. + * + * @param nothing + * @return nothing + * @ingroup buffer + */ +void Modbus::sendTxBuffer() +{ + //uint8_t i = 0; //unused + + // append CRC to message + uint16_t u16crc = calcCRC( u8BufferSize ); + au8Buffer[ u8BufferSize ] = u16crc >> 8; + u8BufferSize++; + au8Buffer[ u8BufferSize ] = u16crc & 0x00ff; + u8BufferSize++; + + // set RS485 transceiver to transmit mode + if (u8txenpin > 1) + { +#if defined(__AVR__) + switch( u8serno ) + { +#if defined(UBRR1H) + case 1: + UCSR1A=UCSR1A |(1 << TXC1); + break; +#endif + +#if defined(UBRR2H) + case 2: + UCSR2A=UCSR2A |(1 << TXC2); + break; +#endif + +#if defined(UBRR3H) + case 3: + UCSR3A=UCSR3A |(1 << TXC3); + break; +#endif + case 0: + default: + UCSR0A=UCSR0A |(1 << TXC0); + break; + } + digitalWrite( u8txenpin, HIGH ); +#endif + } + + // transfer buffer to serial line + if(u8serno<4) + port->write( au8Buffer, u8BufferSize ); + else + softPort->write( au8Buffer, u8BufferSize ); + + // keep RS485 transceiver in transmit mode as long as sending + if (u8txenpin > 1) + { +#if defined(__AVR__) + switch( u8serno ) + { +#if defined(UBRR1H) + case 1: + while (!(UCSR1A & (1 << TXC1))); + break; +#endif + +#if defined(UBRR2H) + case 2: + while (!(UCSR2A & (1 << TXC2))); + break; +#endif + +#if defined(UBRR3H) + case 3: + while (!(UCSR3A & (1 << TXC3))); + break; +#endif + case 0: + default: + while (!(UCSR0A & (1 << TXC0))); + break; + } + + // return RS485 transceiver to receive mode + digitalWrite( u8txenpin, LOW ); +#endif + } + if(u8serno<4) + while(port->read() >= 0); + else + while(softPort->read() >= 0); + + u8BufferSize = 0; + + // set time-out for master + u32timeOut = millis() + (unsigned long) u16timeOut; + + // increase message counter + u16OutCnt++; +} + +/** + * @brief + * This method calculates CRC + * + * @return uint16_t calculated CRC value for the message + * @ingroup buffer + */ +uint16_t Modbus::calcCRC(uint8_t u8length) +{ + unsigned int temp, temp2, flag; + temp = 0xFFFF; + for (unsigned char i = 0; i < u8length; i++) + { + temp = temp ^ au8Buffer[i]; + for (unsigned char j = 1; j <= 8; j++) + { + flag = temp & 0x0001; + temp >>=1; + if (flag) + temp ^= 0xA001; + } + } + // Reverse byte order. + temp2 = temp >> 8; + temp = (temp << 8) | temp2; + temp &= 0xFFFF; + // the returned value is already swapped + // crcLo byte is first & crcHi byte is last + return temp; +} + +/** + * @brief + * This method validates slave incoming messages + * + * @return 0 if OK, EXCEPTION if anything fails + * @ingroup buffer + */ +uint8_t Modbus::validateRequest() +{ + // check message crc vs calculated crc + uint16_t u16MsgCRC = + ((au8Buffer[u8BufferSize - 2] << 8) + | au8Buffer[u8BufferSize - 1]); // combine the crc Low & High bytes + if ( calcCRC( u8BufferSize-2 ) != u16MsgCRC ) + { + u16errCnt ++; + return NO_REPLY; + } + + // check fct code + boolean isSupported = false; + for (uint8_t i = 0; i< sizeof( fctsupported ); i++) + { + if (fctsupported[i] == au8Buffer[FUNC]) + { + isSupported = 1; + break; + } + } + if (!isSupported) + { + u16errCnt ++; + return EXC_FUNC_CODE; + } + + // check start address & nb range + uint16_t u16regs = 0; + uint8_t u8regs; + switch ( au8Buffer[ FUNC ] ) + { + case MB_FC_READ_COILS: + case MB_FC_READ_DISCRETE_INPUT: + case MB_FC_WRITE_MULTIPLE_COILS: + u16regs = word( au8Buffer[ ADD_HI ], au8Buffer[ ADD_LO ]) / 16; + u16regs += word( au8Buffer[ NB_HI ], au8Buffer[ NB_LO ]) /16; + u8regs = (uint8_t) u16regs; + if (u8regs > u8regsize) return EXC_ADDR_RANGE; + break; + case MB_FC_WRITE_COIL: + u16regs = word( au8Buffer[ ADD_HI ], au8Buffer[ ADD_LO ]) / 16; + u8regs = (uint8_t) u16regs; + if (u8regs > u8regsize) return EXC_ADDR_RANGE; + break; + case MB_FC_WRITE_REGISTER : + u16regs = word( au8Buffer[ ADD_HI ], au8Buffer[ ADD_LO ]); + u8regs = (uint8_t) u16regs; + if (u8regs > u8regsize) return EXC_ADDR_RANGE; + break; + case MB_FC_READ_REGISTERS : + case MB_FC_READ_INPUT_REGISTER : + case MB_FC_WRITE_MULTIPLE_REGISTERS : + u16regs = word( au8Buffer[ ADD_HI ], au8Buffer[ ADD_LO ]); + u16regs += word( au8Buffer[ NB_HI ], au8Buffer[ NB_LO ]); + u8regs = (uint8_t) u16regs; + if (u8regs > u8regsize) return EXC_ADDR_RANGE; + break; + } + return 0; // OK, no exception code thrown +} + +/** + * @brief + * This method validates master incoming messages + * + * @return 0 if OK, EXCEPTION if anything fails + * @ingroup buffer + */ +uint8_t Modbus::validateAnswer() +{ + // check message crc vs calculated crc + uint16_t u16MsgCRC = + ((au8Buffer[u8BufferSize - 2] << 8) + | au8Buffer[u8BufferSize - 1]); // combine the crc Low & High bytes + if ( calcCRC( u8BufferSize-2 ) != u16MsgCRC ) + { + u16errCnt ++; + return NO_REPLY; + } + + // check exception + if ((au8Buffer[ FUNC ] & 0x80) != 0) + { + u16errCnt ++; + return ERR_EXCEPTION; + } + + // check fct code + boolean isSupported = false; + for (uint8_t i = 0; i< sizeof( fctsupported ); i++) + { + if (fctsupported[i] == au8Buffer[FUNC]) + { + isSupported = 1; + break; + } + } + if (!isSupported) + { + u16errCnt ++; + return EXC_FUNC_CODE; + } + + return 0; // OK, no exception code thrown +} + +/** + * @brief + * This method builds an exception message + * + * @ingroup buffer + */ +void Modbus::buildException( uint8_t u8exception ) +{ + uint8_t u8func = au8Buffer[ FUNC ]; // get the original FUNC code + + au8Buffer[ ID ] = u8id; + au8Buffer[ FUNC ] = u8func + 0x80; + au8Buffer[ 2 ] = u8exception; + u8BufferSize = EXCEPTION_SIZE; +} + +/** + * This method processes functions 1 & 2 (for master) + * This method puts the slave answer into master data buffer + * + * @ingroup register + * TODO: finish its implementation + */ +void Modbus::get_FC1() +{ + //uint8_t u8byte, i; + //u8byte = 0; + + // for (i=0; i< au8Buffer[ 2 ] /2; i++) { + // au16regs[ i ] = word( + // au8Buffer[ u8byte ], + // au8Buffer[ u8byte +1 ]); + // u8byte += 2; + // } +} + +/** + * This method processes functions 3 & 4 (for master) + * This method puts the slave answer into master data buffer + * + * @ingroup register + */ +void Modbus::get_FC3() +{ + uint8_t u8byte, i; + u8byte = 3; + + for (i=0; i< au8Buffer[ 2 ] /2; i++) + { + au16regs[ i ] = word( + au8Buffer[ u8byte ], + au8Buffer[ u8byte +1 ]); + u8byte += 2; + } +} + +/** + * @brief + * This method processes functions 1 & 2 + * This method reads a bit array and transfers it to the master + * + * @return u8BufferSize Response to master length + * @ingroup discrete + */ +int8_t Modbus::process_FC1( uint16_t *regs, uint8_t u8size ) +{ + uint8_t u8currentRegister, u8currentBit, u8bytesno, u8bitsno; + uint8_t u8CopyBufferSize; + uint16_t u16currentCoil, u16coil; + + // get the first and last coil from the message + uint16_t u16StartCoil = word( au8Buffer[ ADD_HI ], au8Buffer[ ADD_LO ] ); + uint16_t u16Coilno = word( au8Buffer[ NB_HI ], au8Buffer[ NB_LO ] ); + + // put the number of bytes in the outcoming message + u8bytesno = (uint8_t) (u16Coilno / 8); + if (u16Coilno % 8 != 0) u8bytesno ++; + au8Buffer[ ADD_HI ] = u8bytesno; + u8BufferSize = ADD_LO; + + // read each coil from the register map and put its value inside the outcoming message + u8bitsno = 0; + + for (u16currentCoil = 0; u16currentCoil < u16Coilno; u16currentCoil++) + { + u16coil = u16StartCoil + u16currentCoil; + u8currentRegister = (uint8_t) (u16coil / 16); + u8currentBit = (uint8_t) (u16coil % 16); + + bitWrite( + au8Buffer[ u8BufferSize ], + u8bitsno, + bitRead( regs[ u8currentRegister ], u8currentBit ) ); + u8bitsno ++; + + if (u8bitsno > 7) + { + u8bitsno = 0; + u8BufferSize++; + } + } + + // send outcoming message + if (u16Coilno % 8 != 0) u8BufferSize ++; + u8CopyBufferSize = u8BufferSize +2; + sendTxBuffer(); + return u8CopyBufferSize; +} + +/** + * @brief + * This method processes functions 3 & 4 + * This method reads a word array and transfers it to the master + * + * @return u8BufferSize Response to master length + * @ingroup register + */ +int8_t Modbus::process_FC3( uint16_t *regs, uint8_t u8size ) +{ + + uint8_t u8StartAdd = word( au8Buffer[ ADD_HI ], au8Buffer[ ADD_LO ] ); + uint8_t u8regsno = word( au8Buffer[ NB_HI ], au8Buffer[ NB_LO ] ); + uint8_t u8CopyBufferSize; + uint8_t i; + + au8Buffer[ 2 ] = u8regsno * 2; + u8BufferSize = 3; + + for (i = u8StartAdd; i < u8StartAdd + u8regsno; i++) + { + au8Buffer[ u8BufferSize ] = highByte(regs[i]); + u8BufferSize++; + au8Buffer[ u8BufferSize ] = lowByte(regs[i]); + u8BufferSize++; + } + u8CopyBufferSize = u8BufferSize +2; + sendTxBuffer(); + + return u8CopyBufferSize; +} + +/** + * @brief + * This method processes function 5 + * This method writes a value assigned by the master to a single bit + * + * @return u8BufferSize Response to master length + * @ingroup discrete + */ +int8_t Modbus::process_FC5( uint16_t *regs, uint8_t u8size ) +{ + uint8_t u8currentRegister, u8currentBit; + uint8_t u8CopyBufferSize; + uint16_t u16coil = word( au8Buffer[ ADD_HI ], au8Buffer[ ADD_LO ] ); + + // point to the register and its bit + u8currentRegister = (uint8_t) (u16coil / 16); + u8currentBit = (uint8_t) (u16coil % 16); + + // write to coil + bitWrite( + regs[ u8currentRegister ], + u8currentBit, + au8Buffer[ NB_HI ] == 0xff ); + + + // send answer to master + u8BufferSize = 6; + u8CopyBufferSize = u8BufferSize +2; + sendTxBuffer(); + + return u8CopyBufferSize; +} + +/** + * @brief + * This method processes function 6 + * This method writes a value assigned by the master to a single word + * + * @return u8BufferSize Response to master length + * @ingroup register + */ +int8_t Modbus::process_FC6( uint16_t *regs, uint8_t u8size ) +{ + + uint8_t u8add = word( au8Buffer[ ADD_HI ], au8Buffer[ ADD_LO ] ); + uint8_t u8CopyBufferSize; + uint16_t u16val = word( au8Buffer[ NB_HI ], au8Buffer[ NB_LO ] ); + + regs[ u8add ] = u16val; + + // keep the same header + u8BufferSize = RESPONSE_SIZE; + + u8CopyBufferSize = u8BufferSize +2; + sendTxBuffer(); + + return u8CopyBufferSize; +} + +/** + * @brief + * This method processes function 15 + * This method writes a bit array assigned by the master + * + * @return u8BufferSize Response to master length + * @ingroup discrete + */ +int8_t Modbus::process_FC15( uint16_t *regs, uint8_t u8size ) +{ + uint8_t u8currentRegister, u8currentBit, u8frameByte, u8bitsno; + uint8_t u8CopyBufferSize; + uint16_t u16currentCoil, u16coil; + boolean bTemp; + + // get the first and last coil from the message + uint16_t u16StartCoil = word( au8Buffer[ ADD_HI ], au8Buffer[ ADD_LO ] ); + uint16_t u16Coilno = word( au8Buffer[ NB_HI ], au8Buffer[ NB_LO ] ); + + + // read each coil from the register map and put its value inside the outcoming message + u8bitsno = 0; + u8frameByte = 7; + for (u16currentCoil = 0; u16currentCoil < u16Coilno; u16currentCoil++) + { + + u16coil = u16StartCoil + u16currentCoil; + u8currentRegister = (uint8_t) (u16coil / 16); + u8currentBit = (uint8_t) (u16coil % 16); + + bTemp = bitRead( + au8Buffer[ u8frameByte ], + u8bitsno ); + + bitWrite( + regs[ u8currentRegister ], + u8currentBit, + bTemp ); + + u8bitsno ++; + + if (u8bitsno > 7) + { + u8bitsno = 0; + u8frameByte++; + } + } + + // send outcoming message + // it's just a copy of the incomping frame until 6th byte + u8BufferSize = 6; + u8CopyBufferSize = u8BufferSize +2; + sendTxBuffer(); + return u8CopyBufferSize; +} + +/** + * @brief + * This method processes function 16 + * This method writes a word array assigned by the master + * + * @return u8BufferSize Response to master length + * @ingroup register + */ +int8_t Modbus::process_FC16( uint16_t *regs, uint8_t u8size ) +{ + //uint8_t u8func = au8Buffer[ FUNC ]; // get the original FUNC code + uint8_t u8StartAdd = au8Buffer[ ADD_HI ] << 8 | au8Buffer[ ADD_LO ]; + uint8_t u8regsno = au8Buffer[ NB_HI ] << 8 | au8Buffer[ NB_LO ]; + uint8_t u8CopyBufferSize; + uint8_t i; + uint16_t temp; + + // build header + au8Buffer[ NB_HI ] = 0; + au8Buffer[ NB_LO ] = u8regsno; + u8BufferSize = RESPONSE_SIZE; + + // write registers + for (i = 0; i < u8regsno; i++) + { + temp = word( + au8Buffer[ (BYTE_CNT + 1) + i * 2 ], + au8Buffer[ (BYTE_CNT + 2) + i * 2 ]); + + regs[ u8StartAdd + i ] = temp; + } + u8CopyBufferSize = u8BufferSize +2; + sendTxBuffer(); + + return u8CopyBufferSize; +} + +#endif // ModbusRtu_H_ diff --git a/software/firmware/libraries/modbus/README.md b/software/firmware/libraries/modbus/README.md new file mode 100644 index 0000000..990819e --- /dev/null +++ b/software/firmware/libraries/modbus/README.md @@ -0,0 +1,80 @@ +README.txt + +libmodbus is a library that provides a Serial Modbus implementation for Arduino. + +A primary goal was to enable industrial communication for the Arduino in order to link it to industrial devices such as HMIs, CNCs, PLCs, temperature regulators or speed drives. + +now you can use software serial with the update from Helium6072! + +LIBRARY CONTENTS +================================================================= +LICENSE.txt GNU Licence file +keywords.txt Arduino IDE colouring syntax + +/documentation +Library documentation generated with Doxygen. + +/examples +Sample sketches to implement miscellaneous settings: + +/examples/advanced_slave Modbus slave node, which links Arduino pins to the Modbus port. +/examples/RS485_slave Modbus slave adapted to the RS485 port +/examples/simple_master Modbus master node with a single query +/examples/simple_slave Modbus slave node with a link array +/examples/software_serial_simple_master Modbus master node that works via software serial + +INSTALLATION PROCEDURE +================================================================= +Refer to this documentation to Install this library: + +http://arduino.cc/en/Guide/Libraries + +Starting with version 1.0.5, you can install 3rd party libraries in the IDE. + +Do not unzip the downloaded library, leave it as is. + +In the Arduino IDE, navigate to Sketch > Import Library. At the top of the drop down list, select the option to "Add Library". + +You will be prompted to select this zipped library. + +Return to the Sketch > Import Library menu. You should now see the library at the bottom of the drop-down menu. It is ready to be used in your sketch. + +The zip file will have been expanded in the libraries folder in your Arduino sketches directory. + +NB : the library will be available to use in sketches, but examples for the library will not be exposed in the File > Examples until after the IDE has restarted. + + +KNOWN ISSUES +================================================================= +It is not compatible with ARDUINO LEONARDO and not tested under ARDUINO DUE and newer boards. + +TODO List +================================================================= +Common to Master and Slave: + +1) Implement other Serial settings: parity, stop bits, ... + +2) End frame delay, also known as T35 + +3) Test it with several Arduino boards: UNO, Mega, etc.. + +4) Extend it to Leonardo + +Master: + +1) Function code 1 and 2 still not implemented + +2) Function code 15 still not implement + +3) Other codes under development + +New features by Helium6072 29 July 2016 +================================================================= +1) "port->flush();" changed into "while(port->read() >= 0);" + +Since Serial.flush() (port->flush(); in ModbusRtu.h line 287, 337, & 827) no longer empties incoming buffer on 1.6 (Arduino.cc : flush() "Waits for the transmission of outgoing serial data to complete. Prior to Arduino 1.0, this instead removed any buffered incoming serial data.), use "while(port->read() >= 0);" instead. + +2) software serial compatible + +New constructor Modbus::Modbus(uint8_t u8id) and method void Modbus::begin(SoftwareSerial *sPort, long u32speed) that makes using software serial possible. +Check out sexample "software_serial_simple_master" and learn more! \ No newline at end of file diff --git a/software/firmware/libraries/modbus/config b/software/firmware/libraries/modbus/config new file mode 100644 index 0000000..dc27219 --- /dev/null +++ b/software/firmware/libraries/modbus/config @@ -0,0 +1,1890 @@ +# Doxyfile 1.8.4 + +# This file describes the settings to be used by the documentation system +# doxygen (www.doxygen.org) for a project. +# +# All text after a double hash (##) is considered a comment and is placed +# in front of the TAG it is preceding . +# All text after a hash (#) is considered a comment and will be ignored. +# The format is: +# TAG = value [value, ...] +# For lists items can also be appended using: +# TAG += value [value, ...] +# Values that contain spaces should be placed between quotes (" "). + +#--------------------------------------------------------------------------- +# Project related configuration options +#--------------------------------------------------------------------------- + +# This tag specifies the encoding used for all characters in the config file +# that follow. The default is UTF-8 which is also the encoding used for all +# text before the first occurrence of this tag. Doxygen uses libiconv (or the +# iconv built into libc) for the transcoding. See +# http://www.gnu.org/software/libiconv for the list of possible encodings. + +DOXYFILE_ENCODING = UTF-8 + +# The PROJECT_NAME tag is a single word (or sequence of words) that should +# identify the project. Note that if you do not use Doxywizard you need +# to put quotes around the project name if it contains spaces. + +PROJECT_NAME = "My Project" + +# The PROJECT_NUMBER tag can be used to enter a project or revision number. +# This could be handy for archiving the generated documentation or +# if some version control system is used. + +PROJECT_NUMBER = + +# Using the PROJECT_BRIEF tag one can provide an optional one line description +# for a project that appears at the top of each page and should give viewer +# a quick idea about the purpose of the project. Keep the description short. + +PROJECT_BRIEF = + +# With the PROJECT_LOGO tag one can specify an logo or icon that is +# included in the documentation. The maximum height of the logo should not +# exceed 55 pixels and the maximum width should not exceed 200 pixels. +# Doxygen will copy the logo to the output directory. + +PROJECT_LOGO = + +# The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) +# base path where the generated documentation will be put. +# If a relative path is entered, it will be relative to the location +# where doxygen was started. If left blank the current directory will be used. + +OUTPUT_DIRECTORY = + +# If the CREATE_SUBDIRS tag is set to YES, then doxygen will create +# 4096 sub-directories (in 2 levels) under the output directory of each output +# format and will distribute the generated files over these directories. +# Enabling this option can be useful when feeding doxygen a huge amount of +# source files, where putting all generated files in the same directory would +# otherwise cause performance problems for the file system. + +CREATE_SUBDIRS = NO + +# The OUTPUT_LANGUAGE tag is used to specify the language in which all +# documentation generated by doxygen is written. Doxygen will use this +# information to generate all constant output in the proper language. +# The default language is English, other supported languages are: +# Afrikaans, Arabic, Brazilian, Catalan, Chinese, Chinese-Traditional, +# Croatian, Czech, Danish, Dutch, Esperanto, Farsi, Finnish, French, German, +# Greek, Hungarian, Italian, Japanese, Japanese-en (Japanese with English +# messages), Korean, Korean-en, Latvian, Lithuanian, Norwegian, Macedonian, +# Persian, Polish, Portuguese, Romanian, Russian, Serbian, Serbian-Cyrillic, +# Slovak, Slovene, Spanish, Swedish, Ukrainian, and Vietnamese. + +OUTPUT_LANGUAGE = English + +# If the BRIEF_MEMBER_DESC tag is set to YES (the default) Doxygen will +# include brief member descriptions after the members that are listed in +# the file and class documentation (similar to JavaDoc). +# Set to NO to disable this. + +BRIEF_MEMBER_DESC = YES + +# If the REPEAT_BRIEF tag is set to YES (the default) Doxygen will prepend +# the brief description of a member or function before the detailed description. +# Note: if both HIDE_UNDOC_MEMBERS and BRIEF_MEMBER_DESC are set to NO, the +# brief descriptions will be completely suppressed. + +REPEAT_BRIEF = YES + +# This tag implements a quasi-intelligent brief description abbreviator +# that is used to form the text in various listings. Each string +# in this list, if found as the leading text of the brief description, will be +# stripped from the text and the result after processing the whole list, is +# used as the annotated text. Otherwise, the brief description is used as-is. +# If left blank, the following values are used ("$name" is automatically +# replaced with the name of the entity): "The $name class" "The $name widget" +# "The $name file" "is" "provides" "specifies" "contains" +# "represents" "a" "an" "the" + +ABBREVIATE_BRIEF = + +# If the ALWAYS_DETAILED_SEC and REPEAT_BRIEF tags are both set to YES then +# Doxygen will generate a detailed section even if there is only a brief +# description. + +ALWAYS_DETAILED_SEC = NO + +# If the INLINE_INHERITED_MEMB tag is set to YES, doxygen will show all +# inherited members of a class in the documentation of that class as if those +# members were ordinary class members. Constructors, destructors and assignment +# operators of the base classes will not be shown. + +INLINE_INHERITED_MEMB = NO + +# If the FULL_PATH_NAMES tag is set to YES then Doxygen will prepend the full +# path before files name in the file list and in the header files. If set +# to NO the shortest path that makes the file name unique will be used. + +FULL_PATH_NAMES = YES + +# If the FULL_PATH_NAMES tag is set to YES then the STRIP_FROM_PATH tag +# can be used to strip a user-defined part of the path. Stripping is +# only done if one of the specified strings matches the left-hand part of +# the path. The tag can be used to show relative paths in the file list. +# If left blank the directory from which doxygen is run is used as the +# path to strip. Note that you specify absolute paths here, but also +# relative paths, which will be relative from the directory where doxygen is +# started. + +STRIP_FROM_PATH = + +# The STRIP_FROM_INC_PATH tag can be used to strip a user-defined part of +# the path mentioned in the documentation of a class, which tells +# the reader which header file to include in order to use a class. +# If left blank only the name of the header file containing the class +# definition is used. Otherwise one should specify the include paths that +# are normally passed to the compiler using the -I flag. + +STRIP_FROM_INC_PATH = + +# If the SHORT_NAMES tag is set to YES, doxygen will generate much shorter +# (but less readable) file names. This can be useful if your file system +# doesn't support long names like on DOS, Mac, or CD-ROM. + +SHORT_NAMES = NO + +# If the JAVADOC_AUTOBRIEF tag is set to YES then Doxygen +# will interpret the first line (until the first dot) of a JavaDoc-style +# comment as the brief description. If set to NO, the JavaDoc +# comments will behave just like regular Qt-style comments +# (thus requiring an explicit @brief command for a brief description.) + +JAVADOC_AUTOBRIEF = NO + +# If the QT_AUTOBRIEF tag is set to YES then Doxygen will +# interpret the first line (until the first dot) of a Qt-style +# comment as the brief description. If set to NO, the comments +# will behave just like regular Qt-style comments (thus requiring +# an explicit \brief command for a brief description.) + +QT_AUTOBRIEF = NO + +# The MULTILINE_CPP_IS_BRIEF tag can be set to YES to make Doxygen +# treat a multi-line C++ special comment block (i.e. a block of //! or /// +# comments) as a brief description. This used to be the default behaviour. +# The new default is to treat a multi-line C++ comment block as a detailed +# description. Set this tag to YES if you prefer the old behaviour instead. + +MULTILINE_CPP_IS_BRIEF = NO + +# If the INHERIT_DOCS tag is set to YES (the default) then an undocumented +# member inherits the documentation from any documented member that it +# re-implements. + +INHERIT_DOCS = YES + +# If the SEPARATE_MEMBER_PAGES tag is set to YES, then doxygen will produce +# a new page for each member. If set to NO, the documentation of a member will +# be part of the file/class/namespace that contains it. + +SEPARATE_MEMBER_PAGES = NO + +# The TAB_SIZE tag can be used to set the number of spaces in a tab. +# Doxygen uses this value to replace tabs by spaces in code fragments. + +TAB_SIZE = 4 + +# This tag can be used to specify a number of aliases that acts +# as commands in the documentation. An alias has the form "name=value". +# For example adding "sideeffect=\par Side Effects:\n" will allow you to +# put the command \sideeffect (or @sideeffect) in the documentation, which +# will result in a user-defined paragraph with heading "Side Effects:". +# You can put \n's in the value part of an alias to insert newlines. + +ALIASES = + +# This tag can be used to specify a number of word-keyword mappings (TCL only). +# A mapping has the form "name=value". For example adding +# "class=itcl::class" will allow you to use the command class in the +# itcl::class meaning. + +TCL_SUBST = + +# Set the OPTIMIZE_OUTPUT_FOR_C tag to YES if your project consists of C +# sources only. Doxygen will then generate output that is more tailored for C. +# For instance, some of the names that are used will be different. The list +# of all members will be omitted, etc. + +OPTIMIZE_OUTPUT_FOR_C = NO + +# Set the OPTIMIZE_OUTPUT_JAVA tag to YES if your project consists of Java +# sources only. Doxygen will then generate output that is more tailored for +# Java. For instance, namespaces will be presented as packages, qualified +# scopes will look different, etc. + +OPTIMIZE_OUTPUT_JAVA = NO + +# Set the OPTIMIZE_FOR_FORTRAN tag to YES if your project consists of Fortran +# sources only. Doxygen will then generate output that is more tailored for +# Fortran. + +OPTIMIZE_FOR_FORTRAN = NO + +# Set the OPTIMIZE_OUTPUT_VHDL tag to YES if your project consists of VHDL +# sources. Doxygen will then generate output that is tailored for +# VHDL. + +OPTIMIZE_OUTPUT_VHDL = NO + +# Doxygen selects the parser to use depending on the extension of the files it +# parses. With this tag you can assign which parser to use for a given +# extension. Doxygen has a built-in mapping, but you can override or extend it +# using this tag. The format is ext=language, where ext is a file extension, +# and language is one of the parsers supported by doxygen: IDL, Java, +# Javascript, CSharp, C, C++, D, PHP, Objective-C, Python, Fortran, VHDL, C, +# C++. For instance to make doxygen treat .inc files as Fortran files (default +# is PHP), and .f files as C (default is Fortran), use: inc=Fortran f=C. Note +# that for custom extensions you also need to set FILE_PATTERNS otherwise the +# files are not read by doxygen. + +EXTENSION_MAPPING = + +# If MARKDOWN_SUPPORT is enabled (the default) then doxygen pre-processes all +# comments according to the Markdown format, which allows for more readable +# documentation. See http://daringfireball.net/projects/markdown/ for details. +# The output of markdown processing is further processed by doxygen, so you +# can mix doxygen, HTML, and XML commands with Markdown formatting. +# Disable only in case of backward compatibilities issues. + +MARKDOWN_SUPPORT = YES + +# When enabled doxygen tries to link words that correspond to documented +# classes, or namespaces to their corresponding documentation. Such a link can +# be prevented in individual cases by by putting a % sign in front of the word +# or globally by setting AUTOLINK_SUPPORT to NO. + +AUTOLINK_SUPPORT = YES + +# If you use STL classes (i.e. std::string, std::vector, etc.) but do not want +# to include (a tag file for) the STL sources as input, then you should +# set this tag to YES in order to let doxygen match functions declarations and +# definitions whose arguments contain STL classes (e.g. func(std::string); v.s. +# func(std::string) {}). This also makes the inheritance and collaboration +# diagrams that involve STL classes more complete and accurate. + +BUILTIN_STL_SUPPORT = NO + +# If you use Microsoft's C++/CLI language, you should set this option to YES to +# enable parsing support. + +CPP_CLI_SUPPORT = NO + +# Set the SIP_SUPPORT tag to YES if your project consists of sip sources only. +# Doxygen will parse them like normal C++ but will assume all classes use public +# instead of private inheritance when no explicit protection keyword is present. + +SIP_SUPPORT = NO + +# For Microsoft's IDL there are propget and propput attributes to indicate +# getter and setter methods for a property. Setting this option to YES (the +# default) will make doxygen replace the get and set methods by a property in +# the documentation. This will only work if the methods are indeed getting or +# setting a simple type. If this is not the case, or you want to show the +# methods anyway, you should set this option to NO. + +IDL_PROPERTY_SUPPORT = YES + +# If member grouping is used in the documentation and the DISTRIBUTE_GROUP_DOC +# tag is set to YES, then doxygen will reuse the documentation of the first +# member in the group (if any) for the other members of the group. By default +# all members of a group must be documented explicitly. + +DISTRIBUTE_GROUP_DOC = NO + +# Set the SUBGROUPING tag to YES (the default) to allow class member groups of +# the same type (for instance a group of public functions) to be put as a +# subgroup of that type (e.g. under the Public Functions section). Set it to +# NO to prevent subgrouping. Alternatively, this can be done per class using +# the \nosubgrouping command. + +SUBGROUPING = YES + +# When the INLINE_GROUPED_CLASSES tag is set to YES, classes, structs and +# unions are shown inside the group in which they are included (e.g. using +# @ingroup) instead of on a separate page (for HTML and Man pages) or +# section (for LaTeX and RTF). + +INLINE_GROUPED_CLASSES = NO + +# When the INLINE_SIMPLE_STRUCTS tag is set to YES, structs, classes, and +# unions with only public data fields or simple typedef fields will be shown +# inline in the documentation of the scope in which they are defined (i.e. file, +# namespace, or group documentation), provided this scope is documented. If set +# to NO (the default), structs, classes, and unions are shown on a separate +# page (for HTML and Man pages) or section (for LaTeX and RTF). + +INLINE_SIMPLE_STRUCTS = NO + +# When TYPEDEF_HIDES_STRUCT is enabled, a typedef of a struct, union, or enum +# is documented as struct, union, or enum with the name of the typedef. So +# typedef struct TypeS {} TypeT, will appear in the documentation as a struct +# with name TypeT. When disabled the typedef will appear as a member of a file, +# namespace, or class. And the struct will be named TypeS. This can typically +# be useful for C code in case the coding convention dictates that all compound +# types are typedef'ed and only the typedef is referenced, never the tag name. + +TYPEDEF_HIDES_STRUCT = NO + +# The size of the symbol lookup cache can be set using LOOKUP_CACHE_SIZE. This +# cache is used to resolve symbols given their name and scope. Since this can +# be an expensive process and often the same symbol appear multiple times in +# the code, doxygen keeps a cache of pre-resolved symbols. If the cache is too +# small doxygen will become slower. If the cache is too large, memory is wasted. +# The cache size is given by this formula: 2^(16+LOOKUP_CACHE_SIZE). The valid +# range is 0..9, the default is 0, corresponding to a cache size of 2^16 = 65536 +# symbols. + +LOOKUP_CACHE_SIZE = 0 + +#--------------------------------------------------------------------------- +# Build related configuration options +#--------------------------------------------------------------------------- + +# If the EXTRACT_ALL tag is set to YES doxygen will assume all entities in +# documentation are documented, even if no documentation was available. +# Private class members and static file members will be hidden unless +# the EXTRACT_PRIVATE respectively EXTRACT_STATIC tags are set to YES + +EXTRACT_ALL = NO + +# If the EXTRACT_PRIVATE tag is set to YES all private members of a class +# will be included in the documentation. + +EXTRACT_PRIVATE = NO + +# If the EXTRACT_PACKAGE tag is set to YES all members with package or internal +# scope will be included in the documentation. + +EXTRACT_PACKAGE = NO + +# If the EXTRACT_STATIC tag is set to YES all static members of a file +# will be included in the documentation. + +EXTRACT_STATIC = NO + +# If the EXTRACT_LOCAL_CLASSES tag is set to YES classes (and structs) +# defined locally in source files will be included in the documentation. +# If set to NO only classes defined in header files are included. + +EXTRACT_LOCAL_CLASSES = YES + +# This flag is only useful for Objective-C code. When set to YES local +# methods, which are defined in the implementation section but not in +# the interface are included in the documentation. +# If set to NO (the default) only methods in the interface are included. + +EXTRACT_LOCAL_METHODS = NO + +# If this flag is set to YES, the members of anonymous namespaces will be +# extracted and appear in the documentation as a namespace called +# 'anonymous_namespace{file}', where file will be replaced with the base +# name of the file that contains the anonymous namespace. By default +# anonymous namespaces are hidden. + +EXTRACT_ANON_NSPACES = NO + +# If the HIDE_UNDOC_MEMBERS tag is set to YES, Doxygen will hide all +# undocumented members of documented classes, files or namespaces. +# If set to NO (the default) these members will be included in the +# various overviews, but no documentation section is generated. +# This option has no effect if EXTRACT_ALL is enabled. + +HIDE_UNDOC_MEMBERS = NO + +# If the HIDE_UNDOC_CLASSES tag is set to YES, Doxygen will hide all +# undocumented classes that are normally visible in the class hierarchy. +# If set to NO (the default) these classes will be included in the various +# overviews. This option has no effect if EXTRACT_ALL is enabled. + +HIDE_UNDOC_CLASSES = NO + +# If the HIDE_FRIEND_COMPOUNDS tag is set to YES, Doxygen will hide all +# friend (class|struct|union) declarations. +# If set to NO (the default) these declarations will be included in the +# documentation. + +HIDE_FRIEND_COMPOUNDS = NO + +# If the HIDE_IN_BODY_DOCS tag is set to YES, Doxygen will hide any +# documentation blocks found inside the body of a function. +# If set to NO (the default) these blocks will be appended to the +# function's detailed documentation block. + +HIDE_IN_BODY_DOCS = NO + +# The INTERNAL_DOCS tag determines if documentation +# that is typed after a \internal command is included. If the tag is set +# to NO (the default) then the documentation will be excluded. +# Set it to YES to include the internal documentation. + +INTERNAL_DOCS = NO + +# If the CASE_SENSE_NAMES tag is set to NO then Doxygen will only generate +# file names in lower-case letters. If set to YES upper-case letters are also +# allowed. This is useful if you have classes or files whose names only differ +# in case and if your file system supports case sensitive file names. Windows +# and Mac users are advised to set this option to NO. + +CASE_SENSE_NAMES = YES + +# If the HIDE_SCOPE_NAMES tag is set to NO (the default) then Doxygen +# will show members with their full class and namespace scopes in the +# documentation. If set to YES the scope will be hidden. + +HIDE_SCOPE_NAMES = NO + +# If the SHOW_INCLUDE_FILES tag is set to YES (the default) then Doxygen +# will put a list of the files that are included by a file in the documentation +# of that file. + +SHOW_INCLUDE_FILES = YES + +# If the FORCE_LOCAL_INCLUDES tag is set to YES then Doxygen +# will list include files with double quotes in the documentation +# rather than with sharp brackets. + +FORCE_LOCAL_INCLUDES = NO + +# If the INLINE_INFO tag is set to YES (the default) then a tag [inline] +# is inserted in the documentation for inline members. + +INLINE_INFO = YES + +# If the SORT_MEMBER_DOCS tag is set to YES (the default) then doxygen +# will sort the (detailed) documentation of file and class members +# alphabetically by member name. If set to NO the members will appear in +# declaration order. + +SORT_MEMBER_DOCS = YES + +# If the SORT_BRIEF_DOCS tag is set to YES then doxygen will sort the +# brief documentation of file, namespace and class members alphabetically +# by member name. If set to NO (the default) the members will appear in +# declaration order. + +SORT_BRIEF_DOCS = NO + +# If the SORT_MEMBERS_CTORS_1ST tag is set to YES then doxygen +# will sort the (brief and detailed) documentation of class members so that +# constructors and destructors are listed first. If set to NO (the default) +# the constructors will appear in the respective orders defined by +# SORT_MEMBER_DOCS and SORT_BRIEF_DOCS. +# This tag will be ignored for brief docs if SORT_BRIEF_DOCS is set to NO +# and ignored for detailed docs if SORT_MEMBER_DOCS is set to NO. + +SORT_MEMBERS_CTORS_1ST = NO + +# If the SORT_GROUP_NAMES tag is set to YES then doxygen will sort the +# hierarchy of group names into alphabetical order. If set to NO (the default) +# the group names will appear in their defined order. + +SORT_GROUP_NAMES = NO + +# If the SORT_BY_SCOPE_NAME tag is set to YES, the class list will be +# sorted by fully-qualified names, including namespaces. If set to +# NO (the default), the class list will be sorted only by class name, +# not including the namespace part. +# Note: This option is not very useful if HIDE_SCOPE_NAMES is set to YES. +# Note: This option applies only to the class list, not to the +# alphabetical list. + +SORT_BY_SCOPE_NAME = NO + +# If the STRICT_PROTO_MATCHING option is enabled and doxygen fails to +# do proper type resolution of all parameters of a function it will reject a +# match between the prototype and the implementation of a member function even +# if there is only one candidate or it is obvious which candidate to choose +# by doing a simple string match. By disabling STRICT_PROTO_MATCHING doxygen +# will still accept a match between prototype and implementation in such cases. + +STRICT_PROTO_MATCHING = NO + +# The GENERATE_TODOLIST tag can be used to enable (YES) or +# disable (NO) the todo list. This list is created by putting \todo +# commands in the documentation. + +GENERATE_TODOLIST = YES + +# The GENERATE_TESTLIST tag can be used to enable (YES) or +# disable (NO) the test list. This list is created by putting \test +# commands in the documentation. + +GENERATE_TESTLIST = YES + +# The GENERATE_BUGLIST tag can be used to enable (YES) or +# disable (NO) the bug list. This list is created by putting \bug +# commands in the documentation. + +GENERATE_BUGLIST = YES + +# The GENERATE_DEPRECATEDLIST tag can be used to enable (YES) or +# disable (NO) the deprecated list. This list is created by putting +# \deprecated commands in the documentation. + +GENERATE_DEPRECATEDLIST= YES + +# The ENABLED_SECTIONS tag can be used to enable conditional +# documentation sections, marked by \if section-label ... \endif +# and \cond section-label ... \endcond blocks. + +ENABLED_SECTIONS = + +# The MAX_INITIALIZER_LINES tag determines the maximum number of lines +# the initial value of a variable or macro consists of for it to appear in +# the documentation. If the initializer consists of more lines than specified +# here it will be hidden. Use a value of 0 to hide initializers completely. +# The appearance of the initializer of individual variables and macros in the +# documentation can be controlled using \showinitializer or \hideinitializer +# command in the documentation regardless of this setting. + +MAX_INITIALIZER_LINES = 30 + +# Set the SHOW_USED_FILES tag to NO to disable the list of files generated +# at the bottom of the documentation of classes and structs. If set to YES the +# list will mention the files that were used to generate the documentation. + +SHOW_USED_FILES = YES + +# Set the SHOW_FILES tag to NO to disable the generation of the Files page. +# This will remove the Files entry from the Quick Index and from the +# Folder Tree View (if specified). The default is YES. + +SHOW_FILES = YES + +# Set the SHOW_NAMESPACES tag to NO to disable the generation of the +# Namespaces page. +# This will remove the Namespaces entry from the Quick Index +# and from the Folder Tree View (if specified). The default is YES. + +SHOW_NAMESPACES = YES + +# The FILE_VERSION_FILTER tag can be used to specify a program or script that +# doxygen should invoke to get the current version for each file (typically from +# the version control system). Doxygen will invoke the program by executing (via +# popen()) the command , where is the value of +# the FILE_VERSION_FILTER tag, and is the name of an input file +# provided by doxygen. Whatever the program writes to standard output +# is used as the file version. See the manual for examples. + +FILE_VERSION_FILTER = + +# The LAYOUT_FILE tag can be used to specify a layout file which will be parsed +# by doxygen. The layout file controls the global structure of the generated +# output files in an output format independent way. To create the layout file +# that represents doxygen's defaults, run doxygen with the -l option. +# You can optionally specify a file name after the option, if omitted +# DoxygenLayout.xml will be used as the name of the layout file. + +LAYOUT_FILE = + +# The CITE_BIB_FILES tag can be used to specify one or more bib files +# containing the references data. This must be a list of .bib files. The +# .bib extension is automatically appended if omitted. Using this command +# requires the bibtex tool to be installed. See also +# http://en.wikipedia.org/wiki/BibTeX for more info. For LaTeX the style +# of the bibliography can be controlled using LATEX_BIB_STYLE. To use this +# feature you need bibtex and perl available in the search path. Do not use +# file names with spaces, bibtex cannot handle them. + +CITE_BIB_FILES = + +#--------------------------------------------------------------------------- +# configuration options related to warning and progress messages +#--------------------------------------------------------------------------- + +# The QUIET tag can be used to turn on/off the messages that are generated +# by doxygen. Possible values are YES and NO. If left blank NO is used. + +QUIET = NO + +# The WARNINGS tag can be used to turn on/off the warning messages that are +# generated by doxygen. Possible values are YES and NO. If left blank +# NO is used. + +WARNINGS = YES + +# If WARN_IF_UNDOCUMENTED is set to YES, then doxygen will generate warnings +# for undocumented members. If EXTRACT_ALL is set to YES then this flag will +# automatically be disabled. + +WARN_IF_UNDOCUMENTED = YES + +# If WARN_IF_DOC_ERROR is set to YES, doxygen will generate warnings for +# potential errors in the documentation, such as not documenting some +# parameters in a documented function, or documenting parameters that +# don't exist or using markup commands wrongly. + +WARN_IF_DOC_ERROR = YES + +# The WARN_NO_PARAMDOC option can be enabled to get warnings for +# functions that are documented, but have no documentation for their parameters +# or return value. If set to NO (the default) doxygen will only warn about +# wrong or incomplete parameter documentation, but not about the absence of +# documentation. + +WARN_NO_PARAMDOC = NO + +# The WARN_FORMAT tag determines the format of the warning messages that +# doxygen can produce. The string should contain the $file, $line, and $text +# tags, which will be replaced by the file and line number from which the +# warning originated and the warning text. Optionally the format may contain +# $version, which will be replaced by the version of the file (if it could +# be obtained via FILE_VERSION_FILTER) + +WARN_FORMAT = "$file:$line: $text" + +# The WARN_LOGFILE tag can be used to specify a file to which warning +# and error messages should be written. If left blank the output is written +# to stderr. + +WARN_LOGFILE = + +#--------------------------------------------------------------------------- +# configuration options related to the input files +#--------------------------------------------------------------------------- + +# The INPUT tag can be used to specify the files and/or directories that contain +# documented source files. You may enter file names like "myfile.cpp" or +# directories like "/usr/src/myproject". Separate the files or directories +# with spaces. + +INPUT = + +# This tag can be used to specify the character encoding of the source files +# that doxygen parses. Internally doxygen uses the UTF-8 encoding, which is +# also the default input encoding. Doxygen uses libiconv (or the iconv built +# into libc) for the transcoding. See http://www.gnu.org/software/libiconv for +# the list of possible encodings. + +INPUT_ENCODING = UTF-8 + +# If the value of the INPUT tag contains directories, you can use the +# FILE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp +# and *.h) to filter out the source-files in the directories. If left +# blank the following patterns are tested: +# *.c *.cc *.cxx *.cpp *.c++ *.d *.java *.ii *.ixx *.ipp *.i++ *.inl *.h *.hh +# *.hxx *.hpp *.h++ *.idl *.odl *.cs *.php *.php3 *.inc *.m *.mm *.dox *.py +# *.f90 *.f *.for *.vhd *.vhdl + +FILE_PATTERNS = + +# The RECURSIVE tag can be used to turn specify whether or not subdirectories +# should be searched for input files as well. Possible values are YES and NO. +# If left blank NO is used. + +RECURSIVE = NO + +# The EXCLUDE tag can be used to specify files and/or directories that should be +# excluded from the INPUT source files. This way you can easily exclude a +# subdirectory from a directory tree whose root is specified with the INPUT tag. +# Note that relative paths are relative to the directory from which doxygen is +# run. + +EXCLUDE = + +# The EXCLUDE_SYMLINKS tag can be used to select whether or not files or +# directories that are symbolic links (a Unix file system feature) are excluded +# from the input. + +EXCLUDE_SYMLINKS = NO + +# If the value of the INPUT tag contains directories, you can use the +# EXCLUDE_PATTERNS tag to specify one or more wildcard patterns to exclude +# certain files from those directories. Note that the wildcards are matched +# against the file with absolute path, so to exclude all test directories +# for example use the pattern */test/* + +EXCLUDE_PATTERNS = + +# The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names +# (namespaces, classes, functions, etc.) that should be excluded from the +# output. The symbol name can be a fully qualified name, a word, or if the +# wildcard * is used, a substring. Examples: ANamespace, AClass, +# AClass::ANamespace, ANamespace::*Test + +EXCLUDE_SYMBOLS = + +# The EXAMPLE_PATH tag can be used to specify one or more files or +# directories that contain example code fragments that are included (see +# the \include command). + +EXAMPLE_PATH = + +# If the value of the EXAMPLE_PATH tag contains directories, you can use the +# EXAMPLE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp +# and *.h) to filter out the source-files in the directories. If left +# blank all files are included. + +EXAMPLE_PATTERNS = + +# If the EXAMPLE_RECURSIVE tag is set to YES then subdirectories will be +# searched for input files to be used with the \include or \dontinclude +# commands irrespective of the value of the RECURSIVE tag. +# Possible values are YES and NO. If left blank NO is used. + +EXAMPLE_RECURSIVE = NO + +# The IMAGE_PATH tag can be used to specify one or more files or +# directories that contain image that are included in the documentation (see +# the \image command). + +IMAGE_PATH = + +# The INPUT_FILTER tag can be used to specify a program that doxygen should +# invoke to filter for each input file. Doxygen will invoke the filter program +# by executing (via popen()) the command , where +# is the value of the INPUT_FILTER tag, and is the name of an +# input file. Doxygen will then use the output that the filter program writes +# to standard output. +# If FILTER_PATTERNS is specified, this tag will be ignored. +# Note that the filter must not add or remove lines; it is applied before the +# code is scanned, but not when the output code is generated. If lines are added +# or removed, the anchors will not be placed correctly. + +INPUT_FILTER = + +# The FILTER_PATTERNS tag can be used to specify filters on a per file pattern +# basis. +# Doxygen will compare the file name with each pattern and apply the +# filter if there is a match. +# The filters are a list of the form: +# pattern=filter (like *.cpp=my_cpp_filter). See INPUT_FILTER for further +# info on how filters are used. If FILTER_PATTERNS is empty or if +# non of the patterns match the file name, INPUT_FILTER is applied. + +FILTER_PATTERNS = + +# If the FILTER_SOURCE_FILES tag is set to YES, the input filter (if set using +# INPUT_FILTER) will be used to filter the input files when producing source +# files to browse (i.e. when SOURCE_BROWSER is set to YES). + +FILTER_SOURCE_FILES = NO + +# The FILTER_SOURCE_PATTERNS tag can be used to specify source filters per file +# pattern. A pattern will override the setting for FILTER_PATTERN (if any) +# and it is also possible to disable source filtering for a specific pattern +# using *.ext= (so without naming a filter). This option only has effect when +# FILTER_SOURCE_FILES is enabled. + +FILTER_SOURCE_PATTERNS = + +# If the USE_MD_FILE_AS_MAINPAGE tag refers to the name of a markdown file that +# is part of the input, its contents will be placed on the main page +# (index.html). This can be useful if you have a project on for instance GitHub +# and want reuse the introduction page also for the doxygen output. + +USE_MDFILE_AS_MAINPAGE = + +#--------------------------------------------------------------------------- +# configuration options related to source browsing +#--------------------------------------------------------------------------- + +# If the SOURCE_BROWSER tag is set to YES then a list of source files will +# be generated. Documented entities will be cross-referenced with these sources. +# Note: To get rid of all source code in the generated output, make sure also +# VERBATIM_HEADERS is set to NO. + +SOURCE_BROWSER = NO + +# Setting the INLINE_SOURCES tag to YES will include the body +# of functions and classes directly in the documentation. + +INLINE_SOURCES = NO + +# Setting the STRIP_CODE_COMMENTS tag to YES (the default) will instruct +# doxygen to hide any special comment blocks from generated source code +# fragments. Normal C, C++ and Fortran comments will always remain visible. + +STRIP_CODE_COMMENTS = YES + +# If the REFERENCED_BY_RELATION tag is set to YES +# then for each documented function all documented +# functions referencing it will be listed. + +REFERENCED_BY_RELATION = NO + +# If the REFERENCES_RELATION tag is set to YES +# then for each documented function all documented entities +# called/used by that function will be listed. + +REFERENCES_RELATION = NO + +# If the REFERENCES_LINK_SOURCE tag is set to YES (the default) +# and SOURCE_BROWSER tag is set to YES, then the hyperlinks from +# functions in REFERENCES_RELATION and REFERENCED_BY_RELATION lists will +# link to the source code. +# Otherwise they will link to the documentation. + +REFERENCES_LINK_SOURCE = YES + +# If the USE_HTAGS tag is set to YES then the references to source code +# will point to the HTML generated by the htags(1) tool instead of doxygen +# built-in source browser. The htags tool is part of GNU's global source +# tagging system (see http://www.gnu.org/software/global/global.html). You +# will need version 4.8.6 or higher. + +USE_HTAGS = NO + +# If the VERBATIM_HEADERS tag is set to YES (the default) then Doxygen +# will generate a verbatim copy of the header file for each class for +# which an include is specified. Set to NO to disable this. + +VERBATIM_HEADERS = YES + +#--------------------------------------------------------------------------- +# configuration options related to the alphabetical class index +#--------------------------------------------------------------------------- + +# If the ALPHABETICAL_INDEX tag is set to YES, an alphabetical index +# of all compounds will be generated. Enable this if the project +# contains a lot of classes, structs, unions or interfaces. + +ALPHABETICAL_INDEX = YES + +# If the alphabetical index is enabled (see ALPHABETICAL_INDEX) then +# the COLS_IN_ALPHA_INDEX tag can be used to specify the number of columns +# in which this list will be split (can be a number in the range [1..20]) + +COLS_IN_ALPHA_INDEX = 5 + +# In case all classes in a project start with a common prefix, all +# classes will be put under the same header in the alphabetical index. +# The IGNORE_PREFIX tag can be used to specify one or more prefixes that +# should be ignored while generating the index headers. + +IGNORE_PREFIX = + +#--------------------------------------------------------------------------- +# configuration options related to the HTML output +#--------------------------------------------------------------------------- + +# If the GENERATE_HTML tag is set to YES (the default) Doxygen will +# generate HTML output. + +GENERATE_HTML = YES + +# The HTML_OUTPUT tag is used to specify where the HTML docs will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `html' will be used as the default path. + +HTML_OUTPUT = html + +# The HTML_FILE_EXTENSION tag can be used to specify the file extension for +# each generated HTML page (for example: .htm,.php,.asp). If it is left blank +# doxygen will generate files with .html extension. + +HTML_FILE_EXTENSION = .html + +# The HTML_HEADER tag can be used to specify a personal HTML header for +# each generated HTML page. If it is left blank doxygen will generate a +# standard header. Note that when using a custom header you are responsible +# for the proper inclusion of any scripts and style sheets that doxygen +# needs, which is dependent on the configuration options used. +# It is advised to generate a default header using "doxygen -w html +# header.html footer.html stylesheet.css YourConfigFile" and then modify +# that header. Note that the header is subject to change so you typically +# have to redo this when upgrading to a newer version of doxygen or when +# changing the value of configuration settings such as GENERATE_TREEVIEW! + +HTML_HEADER = + +# The HTML_FOOTER tag can be used to specify a personal HTML footer for +# each generated HTML page. If it is left blank doxygen will generate a +# standard footer. + +HTML_FOOTER = + +# The HTML_STYLESHEET tag can be used to specify a user-defined cascading +# style sheet that is used by each HTML page. It can be used to +# fine-tune the look of the HTML output. If left blank doxygen will +# generate a default style sheet. Note that it is recommended to use +# HTML_EXTRA_STYLESHEET instead of this one, as it is more robust and this +# tag will in the future become obsolete. + +HTML_STYLESHEET = + +# The HTML_EXTRA_STYLESHEET tag can be used to specify an additional +# user-defined cascading style sheet that is included after the standard +# style sheets created by doxygen. Using this option one can overrule +# certain style aspects. This is preferred over using HTML_STYLESHEET +# since it does not replace the standard style sheet and is therefor more +# robust against future updates. Doxygen will copy the style sheet file to +# the output directory. + +HTML_EXTRA_STYLESHEET = + +# The HTML_EXTRA_FILES tag can be used to specify one or more extra images or +# other source files which should be copied to the HTML output directory. Note +# that these files will be copied to the base HTML output directory. Use the +# $relpath^ marker in the HTML_HEADER and/or HTML_FOOTER files to load these +# files. In the HTML_STYLESHEET file, use the file name only. Also note that +# the files will be copied as-is; there are no commands or markers available. + +HTML_EXTRA_FILES = + +# The HTML_COLORSTYLE_HUE tag controls the color of the HTML output. +# Doxygen will adjust the colors in the style sheet and background images +# according to this color. Hue is specified as an angle on a colorwheel, +# see http://en.wikipedia.org/wiki/Hue for more information. +# For instance the value 0 represents red, 60 is yellow, 120 is green, +# 180 is cyan, 240 is blue, 300 purple, and 360 is red again. +# The allowed range is 0 to 359. + +HTML_COLORSTYLE_HUE = 220 + +# The HTML_COLORSTYLE_SAT tag controls the purity (or saturation) of +# the colors in the HTML output. For a value of 0 the output will use +# grayscales only. A value of 255 will produce the most vivid colors. + +HTML_COLORSTYLE_SAT = 100 + +# The HTML_COLORSTYLE_GAMMA tag controls the gamma correction applied to +# the luminance component of the colors in the HTML output. Values below +# 100 gradually make the output lighter, whereas values above 100 make +# the output darker. The value divided by 100 is the actual gamma applied, +# so 80 represents a gamma of 0.8, The value 220 represents a gamma of 2.2, +# and 100 does not change the gamma. + +HTML_COLORSTYLE_GAMMA = 80 + +# If the HTML_TIMESTAMP tag is set to YES then the footer of each generated HTML +# page will contain the date and time when the page was generated. Setting +# this to NO can help when comparing the output of multiple runs. + +HTML_TIMESTAMP = YES + +# If the HTML_DYNAMIC_SECTIONS tag is set to YES then the generated HTML +# documentation will contain sections that can be hidden and shown after the +# page has loaded. + +HTML_DYNAMIC_SECTIONS = NO + +# With HTML_INDEX_NUM_ENTRIES one can control the preferred number of +# entries shown in the various tree structured indices initially; the user +# can expand and collapse entries dynamically later on. Doxygen will expand +# the tree to such a level that at most the specified number of entries are +# visible (unless a fully collapsed tree already exceeds this amount). +# So setting the number of entries 1 will produce a full collapsed tree by +# default. 0 is a special value representing an infinite number of entries +# and will result in a full expanded tree by default. + +HTML_INDEX_NUM_ENTRIES = 100 + +# If the GENERATE_DOCSET tag is set to YES, additional index files +# will be generated that can be used as input for Apple's Xcode 3 +# integrated development environment, introduced with OSX 10.5 (Leopard). +# To create a documentation set, doxygen will generate a Makefile in the +# HTML output directory. Running make will produce the docset in that +# directory and running "make install" will install the docset in +# ~/Library/Developer/Shared/Documentation/DocSets so that Xcode will find +# it at startup. +# See http://developer.apple.com/tools/creatingdocsetswithdoxygen.html +# for more information. + +GENERATE_DOCSET = NO + +# When GENERATE_DOCSET tag is set to YES, this tag determines the name of the +# feed. A documentation feed provides an umbrella under which multiple +# documentation sets from a single provider (such as a company or product suite) +# can be grouped. + +DOCSET_FEEDNAME = "Doxygen generated docs" + +# When GENERATE_DOCSET tag is set to YES, this tag specifies a string that +# should uniquely identify the documentation set bundle. This should be a +# reverse domain-name style string, e.g. com.mycompany.MyDocSet. Doxygen +# will append .docset to the name. + +DOCSET_BUNDLE_ID = org.doxygen.Project + +# When GENERATE_PUBLISHER_ID tag specifies a string that should uniquely +# identify the documentation publisher. This should be a reverse domain-name +# style string, e.g. com.mycompany.MyDocSet.documentation. + +DOCSET_PUBLISHER_ID = org.doxygen.Publisher + +# The GENERATE_PUBLISHER_NAME tag identifies the documentation publisher. + +DOCSET_PUBLISHER_NAME = Publisher + +# If the GENERATE_HTMLHELP tag is set to YES, additional index files +# will be generated that can be used as input for tools like the +# Microsoft HTML help workshop to generate a compiled HTML help file (.chm) +# of the generated HTML documentation. + +GENERATE_HTMLHELP = NO + +# If the GENERATE_HTMLHELP tag is set to YES, the CHM_FILE tag can +# be used to specify the file name of the resulting .chm file. You +# can add a path in front of the file if the result should not be +# written to the html output directory. + +CHM_FILE = + +# If the GENERATE_HTMLHELP tag is set to YES, the HHC_LOCATION tag can +# be used to specify the location (absolute path including file name) of +# the HTML help compiler (hhc.exe). If non-empty doxygen will try to run +# the HTML help compiler on the generated index.hhp. + +HHC_LOCATION = + +# If the GENERATE_HTMLHELP tag is set to YES, the GENERATE_CHI flag +# controls if a separate .chi index file is generated (YES) or that +# it should be included in the master .chm file (NO). + +GENERATE_CHI = NO + +# If the GENERATE_HTMLHELP tag is set to YES, the CHM_INDEX_ENCODING +# is used to encode HtmlHelp index (hhk), content (hhc) and project file +# content. + +CHM_INDEX_ENCODING = + +# If the GENERATE_HTMLHELP tag is set to YES, the BINARY_TOC flag +# controls whether a binary table of contents is generated (YES) or a +# normal table of contents (NO) in the .chm file. + +BINARY_TOC = NO + +# The TOC_EXPAND flag can be set to YES to add extra items for group members +# to the contents of the HTML help documentation and to the tree view. + +TOC_EXPAND = NO + +# If the GENERATE_QHP tag is set to YES and both QHP_NAMESPACE and +# QHP_VIRTUAL_FOLDER are set, an additional index file will be generated +# that can be used as input for Qt's qhelpgenerator to generate a +# Qt Compressed Help (.qch) of the generated HTML documentation. + +GENERATE_QHP = NO + +# If the QHG_LOCATION tag is specified, the QCH_FILE tag can +# be used to specify the file name of the resulting .qch file. +# The path specified is relative to the HTML output folder. + +QCH_FILE = + +# The QHP_NAMESPACE tag specifies the namespace to use when generating +# Qt Help Project output. For more information please see +# http://doc.trolltech.com/qthelpproject.html#namespace + +QHP_NAMESPACE = org.doxygen.Project + +# The QHP_VIRTUAL_FOLDER tag specifies the namespace to use when generating +# Qt Help Project output. For more information please see +# http://doc.trolltech.com/qthelpproject.html#virtual-folders + +QHP_VIRTUAL_FOLDER = doc + +# If QHP_CUST_FILTER_NAME is set, it specifies the name of a custom filter to +# add. For more information please see +# http://doc.trolltech.com/qthelpproject.html#custom-filters + +QHP_CUST_FILTER_NAME = + +# The QHP_CUST_FILT_ATTRS tag specifies the list of the attributes of the +# custom filter to add. For more information please see +# +# Qt Help Project / Custom Filters. + +QHP_CUST_FILTER_ATTRS = + +# The QHP_SECT_FILTER_ATTRS tag specifies the list of the attributes this +# project's +# filter section matches. +# +# Qt Help Project / Filter Attributes. + +QHP_SECT_FILTER_ATTRS = + +# If the GENERATE_QHP tag is set to YES, the QHG_LOCATION tag can +# be used to specify the location of Qt's qhelpgenerator. +# If non-empty doxygen will try to run qhelpgenerator on the generated +# .qhp file. + +QHG_LOCATION = + +# If the GENERATE_ECLIPSEHELP tag is set to YES, additional index files +# will be generated, which together with the HTML files, form an Eclipse help +# plugin. To install this plugin and make it available under the help contents +# menu in Eclipse, the contents of the directory containing the HTML and XML +# files needs to be copied into the plugins directory of eclipse. The name of +# the directory within the plugins directory should be the same as +# the ECLIPSE_DOC_ID value. After copying Eclipse needs to be restarted before +# the help appears. + +GENERATE_ECLIPSEHELP = NO + +# A unique identifier for the eclipse help plugin. When installing the plugin +# the directory name containing the HTML and XML files should also have +# this name. + +ECLIPSE_DOC_ID = org.doxygen.Project + +# The DISABLE_INDEX tag can be used to turn on/off the condensed index (tabs) +# at top of each HTML page. The value NO (the default) enables the index and +# the value YES disables it. Since the tabs have the same information as the +# navigation tree you can set this option to NO if you already set +# GENERATE_TREEVIEW to YES. + +DISABLE_INDEX = NO + +# The GENERATE_TREEVIEW tag is used to specify whether a tree-like index +# structure should be generated to display hierarchical information. +# If the tag value is set to YES, a side panel will be generated +# containing a tree-like index structure (just like the one that +# is generated for HTML Help). For this to work a browser that supports +# JavaScript, DHTML, CSS and frames is required (i.e. any modern browser). +# Windows users are probably better off using the HTML help feature. +# Since the tree basically has the same information as the tab index you +# could consider to set DISABLE_INDEX to NO when enabling this option. + +GENERATE_TREEVIEW = NO + +# The ENUM_VALUES_PER_LINE tag can be used to set the number of enum values +# (range [0,1..20]) that doxygen will group on one line in the generated HTML +# documentation. Note that a value of 0 will completely suppress the enum +# values from appearing in the overview section. + +ENUM_VALUES_PER_LINE = 4 + +# If the treeview is enabled (see GENERATE_TREEVIEW) then this tag can be +# used to set the initial width (in pixels) of the frame in which the tree +# is shown. + +TREEVIEW_WIDTH = 250 + +# When the EXT_LINKS_IN_WINDOW option is set to YES doxygen will open +# links to external symbols imported via tag files in a separate window. + +EXT_LINKS_IN_WINDOW = NO + +# Use this tag to change the font size of Latex formulas included +# as images in the HTML documentation. The default is 10. Note that +# when you change the font size after a successful doxygen run you need +# to manually remove any form_*.png images from the HTML output directory +# to force them to be regenerated. + +FORMULA_FONTSIZE = 10 + +# Use the FORMULA_TRANPARENT tag to determine whether or not the images +# generated for formulas are transparent PNGs. Transparent PNGs are +# not supported properly for IE 6.0, but are supported on all modern browsers. +# Note that when changing this option you need to delete any form_*.png files +# in the HTML output before the changes have effect. + +FORMULA_TRANSPARENT = YES + +# Enable the USE_MATHJAX option to render LaTeX formulas using MathJax +# (see http://www.mathjax.org) which uses client side Javascript for the +# rendering instead of using prerendered bitmaps. Use this if you do not +# have LaTeX installed or if you want to formulas look prettier in the HTML +# output. When enabled you may also need to install MathJax separately and +# configure the path to it using the MATHJAX_RELPATH option. + +USE_MATHJAX = NO + +# When MathJax is enabled you can set the default output format to be used for +# the MathJax output. Supported types are HTML-CSS, NativeMML (i.e. MathML) and +# SVG. The default value is HTML-CSS, which is slower, but has the best +# compatibility. + +MATHJAX_FORMAT = HTML-CSS + +# When MathJax is enabled you need to specify the location relative to the +# HTML output directory using the MATHJAX_RELPATH option. The destination +# directory should contain the MathJax.js script. For instance, if the mathjax +# directory is located at the same level as the HTML output directory, then +# MATHJAX_RELPATH should be ../mathjax. The default value points to +# the MathJax Content Delivery Network so you can quickly see the result without +# installing MathJax. +# However, it is strongly recommended to install a local +# copy of MathJax from http://www.mathjax.org before deployment. + +MATHJAX_RELPATH = http://cdn.mathjax.org/mathjax/latest + +# The MATHJAX_EXTENSIONS tag can be used to specify one or MathJax extension +# names that should be enabled during MathJax rendering. + +MATHJAX_EXTENSIONS = + +# The MATHJAX_CODEFILE tag can be used to specify a file with javascript +# pieces of code that will be used on startup of the MathJax code. + +MATHJAX_CODEFILE = + +# When the SEARCHENGINE tag is enabled doxygen will generate a search box +# for the HTML output. The underlying search engine uses javascript +# and DHTML and should work on any modern browser. Note that when using +# HTML help (GENERATE_HTMLHELP), Qt help (GENERATE_QHP), or docsets +# (GENERATE_DOCSET) there is already a search function so this one should +# typically be disabled. For large projects the javascript based search engine +# can be slow, then enabling SERVER_BASED_SEARCH may provide a better solution. + +SEARCHENGINE = YES + +# When the SERVER_BASED_SEARCH tag is enabled the search engine will be +# implemented using a web server instead of a web client using Javascript. +# There are two flavours of web server based search depending on the +# EXTERNAL_SEARCH setting. When disabled, doxygen will generate a PHP script for +# searching and an index file used by the script. When EXTERNAL_SEARCH is +# enabled the indexing and searching needs to be provided by external tools. +# See the manual for details. + +SERVER_BASED_SEARCH = NO + +# When EXTERNAL_SEARCH is enabled doxygen will no longer generate the PHP +# script for searching. Instead the search results are written to an XML file +# which needs to be processed by an external indexer. Doxygen will invoke an +# external search engine pointed to by the SEARCHENGINE_URL option to obtain +# the search results. Doxygen ships with an example indexer (doxyindexer) and +# search engine (doxysearch.cgi) which are based on the open source search +# engine library Xapian. See the manual for configuration details. + +EXTERNAL_SEARCH = NO + +# The SEARCHENGINE_URL should point to a search engine hosted by a web server +# which will returned the search results when EXTERNAL_SEARCH is enabled. +# Doxygen ships with an example search engine (doxysearch) which is based on +# the open source search engine library Xapian. See the manual for configuration +# details. + +SEARCHENGINE_URL = + +# When SERVER_BASED_SEARCH and EXTERNAL_SEARCH are both enabled the unindexed +# search data is written to a file for indexing by an external tool. With the +# SEARCHDATA_FILE tag the name of this file can be specified. + +SEARCHDATA_FILE = searchdata.xml + +# When SERVER_BASED_SEARCH AND EXTERNAL_SEARCH are both enabled the +# EXTERNAL_SEARCH_ID tag can be used as an identifier for the project. This is +# useful in combination with EXTRA_SEARCH_MAPPINGS to search through multiple +# projects and redirect the results back to the right project. + +EXTERNAL_SEARCH_ID = + +# The EXTRA_SEARCH_MAPPINGS tag can be used to enable searching through doxygen +# projects other than the one defined by this configuration file, but that are +# all added to the same external search index. Each project needs to have a +# unique id set via EXTERNAL_SEARCH_ID. The search mapping then maps the id +# of to a relative location where the documentation can be found. +# The format is: EXTRA_SEARCH_MAPPINGS = id1=loc1 id2=loc2 ... + +EXTRA_SEARCH_MAPPINGS = + +#--------------------------------------------------------------------------- +# configuration options related to the LaTeX output +#--------------------------------------------------------------------------- + +# If the GENERATE_LATEX tag is set to YES (the default) Doxygen will +# generate Latex output. + +GENERATE_LATEX = YES + +# The LATEX_OUTPUT tag is used to specify where the LaTeX docs will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `latex' will be used as the default path. + +LATEX_OUTPUT = latex + +# The LATEX_CMD_NAME tag can be used to specify the LaTeX command name to be +# invoked. If left blank `latex' will be used as the default command name. +# Note that when enabling USE_PDFLATEX this option is only used for +# generating bitmaps for formulas in the HTML output, but not in the +# Makefile that is written to the output directory. + +LATEX_CMD_NAME = latex + +# The MAKEINDEX_CMD_NAME tag can be used to specify the command name to +# generate index for LaTeX. If left blank `makeindex' will be used as the +# default command name. + +MAKEINDEX_CMD_NAME = makeindex + +# If the COMPACT_LATEX tag is set to YES Doxygen generates more compact +# LaTeX documents. This may be useful for small projects and may help to +# save some trees in general. + +COMPACT_LATEX = NO + +# The PAPER_TYPE tag can be used to set the paper type that is used +# by the printer. Possible values are: a4, letter, legal and +# executive. If left blank a4 will be used. + +PAPER_TYPE = a4 + +# The EXTRA_PACKAGES tag can be to specify one or more names of LaTeX +# packages that should be included in the LaTeX output. + +EXTRA_PACKAGES = + +# The LATEX_HEADER tag can be used to specify a personal LaTeX header for +# the generated latex document. The header should contain everything until +# the first chapter. If it is left blank doxygen will generate a +# standard header. Notice: only use this tag if you know what you are doing! + +LATEX_HEADER = + +# The LATEX_FOOTER tag can be used to specify a personal LaTeX footer for +# the generated latex document. The footer should contain everything after +# the last chapter. If it is left blank doxygen will generate a +# standard footer. Notice: only use this tag if you know what you are doing! + +LATEX_FOOTER = + +# The LATEX_EXTRA_FILES tag can be used to specify one or more extra images +# or other source files which should be copied to the LaTeX output directory. +# Note that the files will be copied as-is; there are no commands or markers +# available. + +LATEX_EXTRA_FILES = + +# If the PDF_HYPERLINKS tag is set to YES, the LaTeX that is generated +# is prepared for conversion to pdf (using ps2pdf). The pdf file will +# contain links (just like the HTML output) instead of page references +# This makes the output suitable for online browsing using a pdf viewer. + +PDF_HYPERLINKS = YES + +# If the USE_PDFLATEX tag is set to YES, pdflatex will be used instead of +# plain latex in the generated Makefile. Set this option to YES to get a +# higher quality PDF documentation. + +USE_PDFLATEX = YES + +# If the LATEX_BATCHMODE tag is set to YES, doxygen will add the \\batchmode. +# command to the generated LaTeX files. This will instruct LaTeX to keep +# running if errors occur, instead of asking the user for help. +# This option is also used when generating formulas in HTML. + +LATEX_BATCHMODE = NO + +# If LATEX_HIDE_INDICES is set to YES then doxygen will not +# include the index chapters (such as File Index, Compound Index, etc.) +# in the output. + +LATEX_HIDE_INDICES = NO + +# If LATEX_SOURCE_CODE is set to YES then doxygen will include +# source code with syntax highlighting in the LaTeX output. +# Note that which sources are shown also depends on other settings +# such as SOURCE_BROWSER. + +LATEX_SOURCE_CODE = NO + +# The LATEX_BIB_STYLE tag can be used to specify the style to use for the +# bibliography, e.g. plainnat, or ieeetr. The default style is "plain". See +# http://en.wikipedia.org/wiki/BibTeX for more info. + +LATEX_BIB_STYLE = plain + +#--------------------------------------------------------------------------- +# configuration options related to the RTF output +#--------------------------------------------------------------------------- + +# If the GENERATE_RTF tag is set to YES Doxygen will generate RTF output +# The RTF output is optimized for Word 97 and may not look very pretty with +# other RTF readers or editors. + +GENERATE_RTF = NO + +# The RTF_OUTPUT tag is used to specify where the RTF docs will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `rtf' will be used as the default path. + +RTF_OUTPUT = rtf + +# If the COMPACT_RTF tag is set to YES Doxygen generates more compact +# RTF documents. This may be useful for small projects and may help to +# save some trees in general. + +COMPACT_RTF = NO + +# If the RTF_HYPERLINKS tag is set to YES, the RTF that is generated +# will contain hyperlink fields. The RTF file will +# contain links (just like the HTML output) instead of page references. +# This makes the output suitable for online browsing using WORD or other +# programs which support those fields. +# Note: wordpad (write) and others do not support links. + +RTF_HYPERLINKS = NO + +# Load style sheet definitions from file. Syntax is similar to doxygen's +# config file, i.e. a series of assignments. You only have to provide +# replacements, missing definitions are set to their default value. + +RTF_STYLESHEET_FILE = + +# Set optional variables used in the generation of an rtf document. +# Syntax is similar to doxygen's config file. + +RTF_EXTENSIONS_FILE = + +#--------------------------------------------------------------------------- +# configuration options related to the man page output +#--------------------------------------------------------------------------- + +# If the GENERATE_MAN tag is set to YES (the default) Doxygen will +# generate man pages + +GENERATE_MAN = NO + +# The MAN_OUTPUT tag is used to specify where the man pages will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `man' will be used as the default path. + +MAN_OUTPUT = man + +# The MAN_EXTENSION tag determines the extension that is added to +# the generated man pages (default is the subroutine's section .3) + +MAN_EXTENSION = .3 + +# If the MAN_LINKS tag is set to YES and Doxygen generates man output, +# then it will generate one additional man file for each entity +# documented in the real man page(s). These additional files +# only source the real man page, but without them the man command +# would be unable to find the correct page. The default is NO. + +MAN_LINKS = NO + +#--------------------------------------------------------------------------- +# configuration options related to the XML output +#--------------------------------------------------------------------------- + +# If the GENERATE_XML tag is set to YES Doxygen will +# generate an XML file that captures the structure of +# the code including all documentation. + +GENERATE_XML = NO + +# The XML_OUTPUT tag is used to specify where the XML pages will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `xml' will be used as the default path. + +XML_OUTPUT = xml + +# The XML_SCHEMA tag can be used to specify an XML schema, +# which can be used by a validating XML parser to check the +# syntax of the XML files. + +XML_SCHEMA = + +# The XML_DTD tag can be used to specify an XML DTD, +# which can be used by a validating XML parser to check the +# syntax of the XML files. + +XML_DTD = + +# If the XML_PROGRAMLISTING tag is set to YES Doxygen will +# dump the program listings (including syntax highlighting +# and cross-referencing information) to the XML output. Note that +# enabling this will significantly increase the size of the XML output. + +XML_PROGRAMLISTING = YES + +#--------------------------------------------------------------------------- +# configuration options related to the DOCBOOK output +#--------------------------------------------------------------------------- + +# If the GENERATE_DOCBOOK tag is set to YES Doxygen will generate DOCBOOK files +# that can be used to generate PDF. + +GENERATE_DOCBOOK = NO + +# The DOCBOOK_OUTPUT tag is used to specify where the DOCBOOK pages will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be put in +# front of it. If left blank docbook will be used as the default path. + +DOCBOOK_OUTPUT = docbook + +#--------------------------------------------------------------------------- +# configuration options for the AutoGen Definitions output +#--------------------------------------------------------------------------- + +# If the GENERATE_AUTOGEN_DEF tag is set to YES Doxygen will +# generate an AutoGen Definitions (see autogen.sf.net) file +# that captures the structure of the code including all +# documentation. Note that this feature is still experimental +# and incomplete at the moment. + +GENERATE_AUTOGEN_DEF = NO + +#--------------------------------------------------------------------------- +# configuration options related to the Perl module output +#--------------------------------------------------------------------------- + +# If the GENERATE_PERLMOD tag is set to YES Doxygen will +# generate a Perl module file that captures the structure of +# the code including all documentation. Note that this +# feature is still experimental and incomplete at the +# moment. + +GENERATE_PERLMOD = NO + +# If the PERLMOD_LATEX tag is set to YES Doxygen will generate +# the necessary Makefile rules, Perl scripts and LaTeX code to be able +# to generate PDF and DVI output from the Perl module output. + +PERLMOD_LATEX = NO + +# If the PERLMOD_PRETTY tag is set to YES the Perl module output will be +# nicely formatted so it can be parsed by a human reader. +# This is useful +# if you want to understand what is going on. +# On the other hand, if this +# tag is set to NO the size of the Perl module output will be much smaller +# and Perl will parse it just the same. + +PERLMOD_PRETTY = YES + +# The names of the make variables in the generated doxyrules.make file +# are prefixed with the string contained in PERLMOD_MAKEVAR_PREFIX. +# This is useful so different doxyrules.make files included by the same +# Makefile don't overwrite each other's variables. + +PERLMOD_MAKEVAR_PREFIX = + +#--------------------------------------------------------------------------- +# Configuration options related to the preprocessor +#--------------------------------------------------------------------------- + +# If the ENABLE_PREPROCESSING tag is set to YES (the default) Doxygen will +# evaluate all C-preprocessor directives found in the sources and include +# files. + +ENABLE_PREPROCESSING = YES + +# If the MACRO_EXPANSION tag is set to YES Doxygen will expand all macro +# names in the source code. If set to NO (the default) only conditional +# compilation will be performed. Macro expansion can be done in a controlled +# way by setting EXPAND_ONLY_PREDEF to YES. + +MACRO_EXPANSION = NO + +# If the EXPAND_ONLY_PREDEF and MACRO_EXPANSION tags are both set to YES +# then the macro expansion is limited to the macros specified with the +# PREDEFINED and EXPAND_AS_DEFINED tags. + +EXPAND_ONLY_PREDEF = NO + +# If the SEARCH_INCLUDES tag is set to YES (the default) the includes files +# pointed to by INCLUDE_PATH will be searched when a #include is found. + +SEARCH_INCLUDES = YES + +# The INCLUDE_PATH tag can be used to specify one or more directories that +# contain include files that are not input files but should be processed by +# the preprocessor. + +INCLUDE_PATH = + +# You can use the INCLUDE_FILE_PATTERNS tag to specify one or more wildcard +# patterns (like *.h and *.hpp) to filter out the header-files in the +# directories. If left blank, the patterns specified with FILE_PATTERNS will +# be used. + +INCLUDE_FILE_PATTERNS = + +# The PREDEFINED tag can be used to specify one or more macro names that +# are defined before the preprocessor is started (similar to the -D option of +# gcc). The argument of the tag is a list of macros of the form: name +# or name=definition (no spaces). If the definition and the = are +# omitted =1 is assumed. To prevent a macro definition from being +# undefined via #undef or recursively expanded use the := operator +# instead of the = operator. + +PREDEFINED = + +# If the MACRO_EXPANSION and EXPAND_ONLY_PREDEF tags are set to YES then +# this tag can be used to specify a list of macro names that should be expanded. +# The macro definition that is found in the sources will be used. +# Use the PREDEFINED tag if you want to use a different macro definition that +# overrules the definition found in the source code. + +EXPAND_AS_DEFINED = + +# If the SKIP_FUNCTION_MACROS tag is set to YES (the default) then +# doxygen's preprocessor will remove all references to function-like macros +# that are alone on a line, have an all uppercase name, and do not end with a +# semicolon, because these will confuse the parser if not removed. + +SKIP_FUNCTION_MACROS = YES + +#--------------------------------------------------------------------------- +# Configuration::additions related to external references +#--------------------------------------------------------------------------- + +# The TAGFILES option can be used to specify one or more tagfiles. For each +# tag file the location of the external documentation should be added. The +# format of a tag file without this location is as follows: +# +# TAGFILES = file1 file2 ... +# Adding location for the tag files is done as follows: +# +# TAGFILES = file1=loc1 "file2 = loc2" ... +# where "loc1" and "loc2" can be relative or absolute paths +# or URLs. Note that each tag file must have a unique name (where the name does +# NOT include the path). If a tag file is not located in the directory in which +# doxygen is run, you must also specify the path to the tagfile here. + +TAGFILES = + +# When a file name is specified after GENERATE_TAGFILE, doxygen will create +# a tag file that is based on the input files it reads. + +GENERATE_TAGFILE = + +# If the ALLEXTERNALS tag is set to YES all external classes will be listed +# in the class index. If set to NO only the inherited external classes +# will be listed. + +ALLEXTERNALS = NO + +# If the EXTERNAL_GROUPS tag is set to YES all external groups will be listed +# in the modules index. If set to NO, only the current project's groups will +# be listed. + +EXTERNAL_GROUPS = YES + +# If the EXTERNAL_PAGES tag is set to YES all external pages will be listed +# in the related pages index. If set to NO, only the current project's +# pages will be listed. + +EXTERNAL_PAGES = YES + +# The PERL_PATH should be the absolute path and name of the perl script +# interpreter (i.e. the result of `which perl'). + +PERL_PATH = /usr/bin/perl + +#--------------------------------------------------------------------------- +# Configuration options related to the dot tool +#--------------------------------------------------------------------------- + +# If the CLASS_DIAGRAMS tag is set to YES (the default) Doxygen will +# generate a inheritance diagram (in HTML, RTF and LaTeX) for classes with base +# or super classes. Setting the tag to NO turns the diagrams off. Note that +# this option also works with HAVE_DOT disabled, but it is recommended to +# install and use dot, since it yields more powerful graphs. + +CLASS_DIAGRAMS = YES + +# You can define message sequence charts within doxygen comments using the \msc +# command. Doxygen will then run the mscgen tool (see +# http://www.mcternan.me.uk/mscgen/) to produce the chart and insert it in the +# documentation. The MSCGEN_PATH tag allows you to specify the directory where +# the mscgen tool resides. If left empty the tool is assumed to be found in the +# default search path. + +MSCGEN_PATH = + +# If set to YES, the inheritance and collaboration graphs will hide +# inheritance and usage relations if the target is undocumented +# or is not a class. + +HIDE_UNDOC_RELATIONS = YES + +# If you set the HAVE_DOT tag to YES then doxygen will assume the dot tool is +# available from the path. This tool is part of Graphviz, a graph visualization +# toolkit from AT&T and Lucent Bell Labs. The other options in this section +# have no effect if this option is set to NO (the default) + +HAVE_DOT = NO + +# The DOT_NUM_THREADS specifies the number of dot invocations doxygen is +# allowed to run in parallel. When set to 0 (the default) doxygen will +# base this on the number of processors available in the system. You can set it +# explicitly to a value larger than 0 to get control over the balance +# between CPU load and processing speed. + +DOT_NUM_THREADS = 0 + +# By default doxygen will use the Helvetica font for all dot files that +# doxygen generates. When you want a differently looking font you can specify +# the font name using DOT_FONTNAME. You need to make sure dot is able to find +# the font, which can be done by putting it in a standard location or by setting +# the DOTFONTPATH environment variable or by setting DOT_FONTPATH to the +# directory containing the font. + +DOT_FONTNAME = Helvetica + +# The DOT_FONTSIZE tag can be used to set the size of the font of dot graphs. +# The default size is 10pt. + +DOT_FONTSIZE = 10 + +# By default doxygen will tell dot to use the Helvetica font. +# If you specify a different font using DOT_FONTNAME you can use DOT_FONTPATH to +# set the path where dot can find it. + +DOT_FONTPATH = + +# If the CLASS_GRAPH and HAVE_DOT tags are set to YES then doxygen +# will generate a graph for each documented class showing the direct and +# indirect inheritance relations. Setting this tag to YES will force the +# CLASS_DIAGRAMS tag to NO. + +CLASS_GRAPH = YES + +# If the COLLABORATION_GRAPH and HAVE_DOT tags are set to YES then doxygen +# will generate a graph for each documented class showing the direct and +# indirect implementation dependencies (inheritance, containment, and +# class references variables) of the class with other documented classes. + +COLLABORATION_GRAPH = YES + +# If the GROUP_GRAPHS and HAVE_DOT tags are set to YES then doxygen +# will generate a graph for groups, showing the direct groups dependencies + +GROUP_GRAPHS = YES + +# If the UML_LOOK tag is set to YES doxygen will generate inheritance and +# collaboration diagrams in a style similar to the OMG's Unified Modeling +# Language. + +UML_LOOK = NO + +# If the UML_LOOK tag is enabled, the fields and methods are shown inside +# the class node. If there are many fields or methods and many nodes the +# graph may become too big to be useful. The UML_LIMIT_NUM_FIELDS +# threshold limits the number of items for each type to make the size more +# manageable. Set this to 0 for no limit. Note that the threshold may be +# exceeded by 50% before the limit is enforced. + +UML_LIMIT_NUM_FIELDS = 10 + +# If set to YES, the inheritance and collaboration graphs will show the +# relations between templates and their instances. + +TEMPLATE_RELATIONS = NO + +# If the ENABLE_PREPROCESSING, SEARCH_INCLUDES, INCLUDE_GRAPH, and HAVE_DOT +# tags are set to YES then doxygen will generate a graph for each documented +# file showing the direct and indirect include dependencies of the file with +# other documented files. + +INCLUDE_GRAPH = YES + +# If the ENABLE_PREPROCESSING, SEARCH_INCLUDES, INCLUDED_BY_GRAPH, and +# HAVE_DOT tags are set to YES then doxygen will generate a graph for each +# documented header file showing the documented files that directly or +# indirectly include this file. + +INCLUDED_BY_GRAPH = YES + +# If the CALL_GRAPH and HAVE_DOT options are set to YES then +# doxygen will generate a call dependency graph for every global function +# or class method. Note that enabling this option will significantly increase +# the time of a run. So in most cases it will be better to enable call graphs +# for selected functions only using the \callgraph command. + +CALL_GRAPH = NO + +# If the CALLER_GRAPH and HAVE_DOT tags are set to YES then +# doxygen will generate a caller dependency graph for every global function +# or class method. Note that enabling this option will significantly increase +# the time of a run. So in most cases it will be better to enable caller +# graphs for selected functions only using the \callergraph command. + +CALLER_GRAPH = NO + +# If the GRAPHICAL_HIERARCHY and HAVE_DOT tags are set to YES then doxygen +# will generate a graphical hierarchy of all classes instead of a textual one. + +GRAPHICAL_HIERARCHY = YES + +# If the DIRECTORY_GRAPH and HAVE_DOT tags are set to YES +# then doxygen will show the dependencies a directory has on other directories +# in a graphical way. The dependency relations are determined by the #include +# relations between the files in the directories. + +DIRECTORY_GRAPH = YES + +# The DOT_IMAGE_FORMAT tag can be used to set the image format of the images +# generated by dot. Possible values are svg, png, jpg, or gif. +# If left blank png will be used. If you choose svg you need to set +# HTML_FILE_EXTENSION to xhtml in order to make the SVG files +# visible in IE 9+ (other browsers do not have this requirement). + +DOT_IMAGE_FORMAT = png + +# If DOT_IMAGE_FORMAT is set to svg, then this option can be set to YES to +# enable generation of interactive SVG images that allow zooming and panning. +# Note that this requires a modern browser other than Internet Explorer. +# Tested and working are Firefox, Chrome, Safari, and Opera. For IE 9+ you +# need to set HTML_FILE_EXTENSION to xhtml in order to make the SVG files +# visible. Older versions of IE do not have SVG support. + +INTERACTIVE_SVG = NO + +# The tag DOT_PATH can be used to specify the path where the dot tool can be +# found. If left blank, it is assumed the dot tool can be found in the path. + +DOT_PATH = + +# The DOTFILE_DIRS tag can be used to specify one or more directories that +# contain dot files that are included in the documentation (see the +# \dotfile command). + +DOTFILE_DIRS = + +# The MSCFILE_DIRS tag can be used to specify one or more directories that +# contain msc files that are included in the documentation (see the +# \mscfile command). + +MSCFILE_DIRS = + +# The DOT_GRAPH_MAX_NODES tag can be used to set the maximum number of +# nodes that will be shown in the graph. If the number of nodes in a graph +# becomes larger than this value, doxygen will truncate the graph, which is +# visualized by representing a node as a red box. Note that doxygen if the +# number of direct children of the root node in a graph is already larger than +# DOT_GRAPH_MAX_NODES then the graph will not be shown at all. Also note +# that the size of a graph can be further restricted by MAX_DOT_GRAPH_DEPTH. + +DOT_GRAPH_MAX_NODES = 50 + +# The MAX_DOT_GRAPH_DEPTH tag can be used to set the maximum depth of the +# graphs generated by dot. A depth value of 3 means that only nodes reachable +# from the root by following a path via at most 3 edges will be shown. Nodes +# that lay further from the root node will be omitted. Note that setting this +# option to 1 or 2 may greatly reduce the computation time needed for large +# code bases. Also note that the size of a graph can be further restricted by +# DOT_GRAPH_MAX_NODES. Using a depth of 0 means no depth restriction. + +MAX_DOT_GRAPH_DEPTH = 0 + +# Set the DOT_TRANSPARENT tag to YES to generate images with a transparent +# background. This is disabled by default, because dot on Windows does not +# seem to support this out of the box. Warning: Depending on the platform used, +# enabling this option may lead to badly anti-aliased labels on the edges of +# a graph (i.e. they become hard to read). + +DOT_TRANSPARENT = NO + +# Set the DOT_MULTI_TARGETS tag to YES allow dot to generate multiple output +# files in one run (i.e. multiple -o and -T options on the command line). This +# makes dot run faster, but since only newer versions of dot (>1.8.10) +# support this, this feature is disabled by default. + +DOT_MULTI_TARGETS = YES + +# If the GENERATE_LEGEND tag is set to YES (the default) Doxygen will +# generate a legend page explaining the meaning of the various boxes and +# arrows in the dot generated graphs. + +GENERATE_LEGEND = YES + +# If the DOT_CLEANUP tag is set to YES (the default) Doxygen will +# remove the intermediate dot files that are used to generate +# the various graphs. + +DOT_CLEANUP = YES diff --git a/software/firmware/libraries/modbus/documentation/html/_modbus_rtu_8h.html b/software/firmware/libraries/modbus/documentation/html/_modbus_rtu_8h.html new file mode 100644 index 0000000..ff65d96 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/html/_modbus_rtu_8h.html @@ -0,0 +1,400 @@ + + + + + + +Modbus Master and Slave for Arduino: ModbusRtu.h File Reference + + + + + + +
+
+ + + + + + +
+
Modbus Master and Slave for Arduino +  1.2 +
+
Arduino library for implementing a Modbus Master or Slave through Serial port
+
+
+ + + + +
+
+ +
+
ModbusRtu.h File Reference
+
+
+ +

Go to the source code of this file.

+ + + + + + + + +

+Classes

struct  modbus_t
 Master query structure: This includes all the necessary fields to make the Master generate a Modbus query. A Master may keep several of these structures and send them cyclically or use them according to program needs. More...
 
class  Modbus
 Arduino class library for communicating with Modbus devices over USB/RS232/485 (via RTU protocol). More...
 
+ + + + + + +

+Macros

#define T35   5
 
#define MAX_BUFFER   64
 maximum size for the communication buffer in bytes More...
 
+ + + + + + + + + + + + + + + +

+Enumerations

enum  { RESPONSE_SIZE = 6, +EXCEPTION_SIZE = 3, +CHECKSUM_SIZE = 2 + }
 
enum  MESSAGE {
+  ID = 0, +FUNC, +ADD_HI, +ADD_LO, +
+  NB_HI, +NB_LO, +BYTE_CNT +
+ }
 Indexes to telegram frame positions. More...
 
enum  MB_FC {
+  MB_FC_NONE = 0, +MB_FC_READ_COILS = 1, +MB_FC_READ_DISCRETE_INPUT = 2, +MB_FC_READ_REGISTERS = 3, +
+  MB_FC_READ_INPUT_REGISTER = 4, +MB_FC_WRITE_COIL = 5, +MB_FC_WRITE_REGISTER = 6, +MB_FC_WRITE_MULTIPLE_COILS = 15, +
+  MB_FC_WRITE_MULTIPLE_REGISTERS = 16 +
+ }
 Modbus function codes summary. These are the implement function codes either for Master or for Slave. More...
 
enum  COM_STATES { COM_IDLE = 0, +COM_WAITING = 1 + }
 
enum  ERR_LIST {
+  ERR_NOT_MASTER = -1, +ERR_POLLING = -2, +ERR_BUFF_OVERFLOW = -3, +ERR_BAD_CRC = -4, +
+  ERR_EXCEPTION = -5 +
+ }
 
enum  {
+  NO_REPLY = 255, +EXC_FUNC_CODE = 1, +EXC_ADDR_RANGE = 2, +EXC_REGS_QUANT = 3, +
+  EXC_EXECUTE = 4 +
+ }
 
+ + + +

+Variables

const unsigned char fctsupported []
 
+

Detailed Description

+
Version
1.2
+
Date
2014.09.09
+
Author
Samuel Marco i Armengol samma.nosp@m.rcoa.nosp@m.rmeng.nosp@m.ol@g.nosp@m.mail..nosp@m.com
+

Arduino library for communicating with Modbus devices over RS232/USB/485 via RTU protocol.

+

Further information: http://modbus.org/ http://modbus.org/docs/Modbus_over_serial_line_V1_02.pdf

+

This library is free software; you can redistribute it and/or modify it under the terms of the GNU Lesser General Public License as published by the Free Software Foundation; version 2.1 of the License.

+

This library is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for more details.

+

You should have received a copy of the GNU Lesser General Public License along with this library; if not, write to the Free Software Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA

+ +

Definition in file ModbusRtu.h.

+

Macro Definition Documentation

+ +
+
+ + + + +
#define MAX_BUFFER   64
+
+ +

maximum size for the communication buffer in bytes

+ +

Definition at line 133 of file ModbusRtu.h.

+ +
+
+ +
+
+ + + + +
#define T35   5
+
+ +

Definition at line 132 of file ModbusRtu.h.

+ +
+
+

Enumeration Type Documentation

+ +
+
+ + + + +
anonymous enum
+
+ + + + +
Enumerator
RESPONSE_SIZE  +
EXCEPTION_SIZE  +
CHECKSUM_SIZE  +
+ +

Definition at line 57 of file ModbusRtu.h.

+ +
+
+ +
+
+ + + + +
anonymous enum
+
+ + + + + + +
Enumerator
NO_REPLY  +
EXC_FUNC_CODE  +
EXC_ADDR_RANGE  +
EXC_REGS_QUANT  +
EXC_EXECUTE  +
+ +

Definition at line 113 of file ModbusRtu.h.

+ +
+
+ +
+
+ + + + +
enum COM_STATES
+
+ + + +
Enumerator
COM_IDLE  +
COM_WAITING  +
+ +

Definition at line 99 of file ModbusRtu.h.

+ +
+
+ +
+
+ + + + +
enum ERR_LIST
+
+ + + + + + +
Enumerator
ERR_NOT_MASTER  +
ERR_POLLING  +
ERR_BUFF_OVERFLOW  +
ERR_BAD_CRC  +
ERR_EXCEPTION  +
+ +

Definition at line 105 of file ModbusRtu.h.

+ +
+
+ +
+
+ + + + +
enum MB_FC
+
+ +

Modbus function codes summary. These are the implement function codes either for Master or for Slave.

+
See Also
also fctsupported
+
+also modbus_t
+ + + + + + + + + + +
Enumerator
MB_FC_NONE  +

null operator

+
MB_FC_READ_COILS  +

FCT=1 -> read coils or digital outputs

+
MB_FC_READ_DISCRETE_INPUT  +

FCT=2 -> read digital inputs

+
MB_FC_READ_REGISTERS  +

FCT=3 -> read registers or analog outputs

+
MB_FC_READ_INPUT_REGISTER  +

FCT=4 -> read analog inputs

+
MB_FC_WRITE_COIL  +

FCT=5 -> write single coil or output

+
MB_FC_WRITE_REGISTER  +

FCT=6 -> write single register

+
MB_FC_WRITE_MULTIPLE_COILS  +

FCT=15 -> write multiple coils or outputs

+
MB_FC_WRITE_MULTIPLE_REGISTERS  +

FCT=16 -> write multiple registers

+
+ +

Definition at line 87 of file ModbusRtu.h.

+ +
+
+ +
+
+ + + + +
enum MESSAGE
+
+ +

Indexes to telegram frame positions.

+ + + + + + + + +
Enumerator
ID  +

ID field.

+
FUNC  +

Function code position.

+
ADD_HI  +

Address high byte.

+
ADD_LO  +

Address low byte.

+
NB_HI  +

Number of coils or registers high byte.

+
NB_LO  +

Number of coils or registers low byte.

+
BYTE_CNT  +

byte counter

+
+ +

Definition at line 68 of file ModbusRtu.h.

+ +
+
+

Variable Documentation

+ +
+
+ + + + +
const unsigned char fctsupported[]
+
+
+
+ + + + diff --git a/software/firmware/libraries/modbus/documentation/html/_modbus_rtu_8h_source.html b/software/firmware/libraries/modbus/documentation/html/_modbus_rtu_8h_source.html new file mode 100644 index 0000000..d83da36 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/html/_modbus_rtu_8h_source.html @@ -0,0 +1,917 @@ + + + + + + +Modbus Master and Slave for Arduino: ModbusRtu.h Source File + + + + + + +
+
+ + + + + + +
+
Modbus Master and Slave for Arduino +  1.2 +
+
Arduino library for implementing a Modbus Master or Slave through Serial port
+
+
+ + + + +
+
+
+
ModbusRtu.h
+
+
+Go to the documentation of this file.
1 
+
48 typedef struct {
+
49  uint8_t u8id;
+
50  uint8_t u8fct;
+
51  uint16_t u16RegAdd;
+
52  uint16_t u16CoilsNo;
+
53  uint16_t *au16reg;
+
54 }
+
55 modbus_t;
+
56 
+
57 enum {
+ + + +
61 };
+
62 
+
68 enum MESSAGE {
+
69  ID = 0,
+
70  FUNC,
+ + + + + +
76 };
+
77 
+
87 enum MB_FC {
+
88  MB_FC_NONE = 0,
+ + + + + + + + +
97 };
+
98 
+
99 enum COM_STATES {
+
100  COM_IDLE = 0,
+ +
102 
+
103 };
+
104 
+
105 enum ERR_LIST {
+ + + + + +
111 };
+
112 
+
113 enum {
+
114  NO_REPLY = 255,
+ + + + +
119 };
+
120 
+
121 const unsigned char fctsupported[] = {
+ + + + + + + + +
130 };
+
131 
+
132 #define T35 5
+
133 #define MAX_BUFFER 64
+
134 
+
135 
+
141 class Modbus {
+
142 private:
+
143  HardwareSerial *port;
+
144  uint8_t u8id;
+
145  uint8_t u8serno;
+
146  uint8_t u8txenpin;
+
147  uint8_t u8state;
+
148  uint8_t u8lastError;
+
149  uint8_t au8Buffer[MAX_BUFFER];
+
150  uint8_t u8BufferSize;
+
151  uint8_t u8lastRec;
+
152  uint16_t *au16regs;
+
153  uint16_t u16InCnt, u16OutCnt, u16errCnt;
+
154  uint16_t u16timeOut;
+
155  uint32_t u32time, u32timeOut;
+
156  uint8_t u8regsize;
+
157 
+
158  void init(uint8_t u8id, uint8_t u8serno, uint8_t u8txenpin);
+
159  void sendTxBuffer();
+
160  int8_t getRxBuffer();
+
161  uint16_t calcCRC(uint8_t u8length);
+
162  uint8_t validateAnswer();
+
163  uint8_t validateRequest();
+
164  void get_FC1();
+
165  void get_FC3();
+
166  int8_t process_FC1( uint16_t *regs, uint8_t u8size );
+
167  int8_t process_FC3( uint16_t *regs, uint8_t u8size );
+
168  int8_t process_FC5( uint16_t *regs, uint8_t u8size );
+
169  int8_t process_FC6( uint16_t *regs, uint8_t u8size );
+
170  int8_t process_FC15( uint16_t *regs, uint8_t u8size );
+
171  int8_t process_FC16( uint16_t *regs, uint8_t u8size );
+
172  void buildException( uint8_t u8exception ); // build exception message
+
173 
+
174 public:
+
175  Modbus();
+
176  Modbus(uint8_t u8id, uint8_t u8serno);
+
177  Modbus(uint8_t u8id, uint8_t u8serno, uint8_t u8txenpin);
+
178  void begin(long u32speed);
+
179  void begin();
+
180  void setTimeOut( uint16_t u16timeout);
+
181  uint16_t getTimeOut();
+
182  boolean getTimeOutState();
+
183  int8_t query( modbus_t telegram );
+
184  int8_t poll();
+
185  int8_t poll( uint16_t *regs, uint8_t u8size );
+
186  uint16_t getInCnt();
+
187  uint16_t getOutCnt();
+
188  uint16_t getErrCnt();
+
189  uint8_t getID();
+
190  uint8_t getState();
+
191  uint8_t getLastError();
+
192  void setID( uint8_t u8id );
+
193  void end();
+
194 };
+
195 
+
196 /* _____PUBLIC FUNCTIONS_____________________________________________________ */
+
197 
+ +
205  init(0, 0, 0);
+
206 }
+
207 
+
218 Modbus::Modbus(uint8_t u8id, uint8_t u8serno) {
+
219  init(u8id, u8serno, 0);
+
220 }
+
221 
+
234 Modbus::Modbus(uint8_t u8id, uint8_t u8serno, uint8_t u8txenpin) {
+
235  init(u8id, u8serno, u8txenpin);
+
236 }
+
237 
+
250 void Modbus::begin(long u32speed) {
+
251 
+
252  switch( u8serno ) {
+
253 #if defined(UBRR1H)
+
254  case 1:
+
255  port = &Serial1;
+
256  break;
+
257 #endif
+
258 
+
259 #if defined(UBRR2H)
+
260  case 2:
+
261  port = &Serial2;
+
262  break;
+
263 #endif
+
264 
+
265 #if defined(UBRR3H)
+
266  case 3:
+
267  port = &Serial3;
+
268  break;
+
269 #endif
+
270  case 0:
+
271  default:
+
272  port = &Serial;
+
273  break;
+
274  }
+
275 
+
276  // port->begin(u32speed, u8config);
+
277  port->begin(u32speed);
+
278  if (u8txenpin > 1) { // pin 0 & pin 1 are reserved for RX/TX
+
279  // return RS485 transceiver to transmit mode
+
280  pinMode(u8txenpin, OUTPUT);
+
281  digitalWrite(u8txenpin, LOW);
+
282  }
+
283 
+
284  port->flush();
+
285  u8lastRec = u8BufferSize = 0;
+
286  u16InCnt = u16OutCnt = u16errCnt = 0;
+
287 }
+
288 
+ +
300  begin(19200);
+
301 }
+
302 
+
310 void Modbus::setID( uint8_t u8id) {
+
311  if (( u8id != 0) && (u8id <= 247)) {
+
312  this->u8id = u8id;
+
313  }
+
314 }
+
315 
+
323 uint8_t Modbus::getID() {
+
324  return this->u8id;
+
325 }
+
326 
+
338 void Modbus::setTimeOut( uint16_t u16timeOut) {
+
339  this->u16timeOut = u16timeOut;
+
340 }
+
341 
+ +
351  return (millis() > u32timeOut);
+
352 }
+
353 
+
362 uint16_t Modbus::getInCnt() {
+
363  return u16InCnt;
+
364 }
+
365 
+
374 uint16_t Modbus::getOutCnt() {
+
375  return u16OutCnt;
+
376 }
+
377 
+
386 uint16_t Modbus::getErrCnt() {
+
387  return u16errCnt;
+
388 }
+
389 
+
396 uint8_t Modbus::getState() {
+
397  return u8state;
+
398 }
+
399 
+ +
410  return u8lastError;
+
411 }
+
412 
+
425 int8_t Modbus::query( modbus_t telegram ) {
+
426  uint8_t u8regsno, u8bytesno;
+
427  if (u8id!=0) return -2;
+
428  if (u8state != COM_IDLE) return -1;
+
429 
+
430  if ((telegram.u8id==0) || (telegram.u8id>247)) return -3;
+
431 
+
432  au16regs = telegram.au16reg;
+
433 
+
434  // telegram header
+
435  au8Buffer[ ID ] = telegram.u8id;
+
436  au8Buffer[ FUNC ] = telegram.u8fct;
+
437  au8Buffer[ ADD_HI ] = highByte(telegram.u16RegAdd );
+
438  au8Buffer[ ADD_LO ] = lowByte( telegram.u16RegAdd );
+
439 
+
440  switch( telegram.u8fct ) {
+
441  case MB_FC_READ_COILS:
+ + + +
445  au8Buffer[ NB_HI ] = highByte(telegram.u16CoilsNo );
+
446  au8Buffer[ NB_LO ] = lowByte( telegram.u16CoilsNo );
+
447  u8BufferSize = 6;
+
448  break;
+
449  case MB_FC_WRITE_COIL:
+
450  au8Buffer[ NB_HI ] = ((au16regs[0] > 0) ? 0xff : 0);
+
451  au8Buffer[ NB_LO ] = 0;
+
452  u8BufferSize = 6;
+
453  break;
+ +
455  au8Buffer[ NB_HI ] = highByte(au16regs[0]);
+
456  au8Buffer[ NB_LO ] = lowByte(au16regs[0]);
+
457  u8BufferSize = 6;
+
458  break;
+
459  case MB_FC_WRITE_MULTIPLE_COILS: // TODO: implement "sending coils"
+
460  u8regsno = telegram.u16CoilsNo / 16;
+
461  u8bytesno = u8regsno * 2;
+
462  if ((telegram.u16CoilsNo % 16) != 0) {
+
463  u8bytesno++;
+
464  u8regsno++;
+
465  }
+
466 
+
467  au8Buffer[ NB_HI ] = highByte(telegram.u16CoilsNo );
+
468  au8Buffer[ NB_LO ] = lowByte( telegram.u16CoilsNo );
+
469  au8Buffer[ NB_LO+1 ] = u8bytesno;
+
470  u8BufferSize = 7;
+
471 
+
472  u8regsno = u8bytesno = 0; // now auxiliary registers
+
473  for (uint16_t i = 0; i < telegram.u16CoilsNo; i++) {
+
474 
+
475 
+
476  }
+
477  break;
+
478 
+ +
480  au8Buffer[ NB_HI ] = highByte(telegram.u16CoilsNo );
+
481  au8Buffer[ NB_LO ] = lowByte( telegram.u16CoilsNo );
+
482  au8Buffer[ NB_LO+1 ] = (uint8_t) ( telegram.u16CoilsNo * 2 );
+
483  u8BufferSize = 7;
+
484 
+
485  for (uint16_t i=0; i< telegram.u16CoilsNo; i++) {
+
486  au8Buffer[ u8BufferSize ] = highByte( au16regs[ i ] );
+
487  u8BufferSize++;
+
488  au8Buffer[ u8BufferSize ] = lowByte( au16regs[ i ] );
+
489  u8BufferSize++;
+
490  }
+
491  break;
+
492  }
+
493 
+
494  sendTxBuffer();
+
495  u8state = COM_WAITING;
+
496  return 0;
+
497 }
+
498 
+
513 int8_t Modbus::poll() {
+
514  // check if there is any incoming frame
+
515  uint8_t u8current = port->available();
+
516 
+
517  if (millis() > u32timeOut) {
+
518  u8state = COM_IDLE;
+
519  u8lastError = NO_REPLY;
+
520  u16errCnt++;
+
521  return 0;
+
522  }
+
523 
+
524  if (u8current == 0) return 0;
+
525 
+
526  // check T35 after frame end or still no frame end
+
527  if (u8current != u8lastRec) {
+
528  u8lastRec = u8current;
+
529  u32time = millis() + T35;
+
530  return 0;
+
531  }
+
532  if (millis() < u32time) return 0;
+
533 
+
534  // transfer Serial buffer frame to auBuffer
+
535  u8lastRec = 0;
+
536  int8_t i8state = getRxBuffer();
+
537  if (i8state < 7) {
+
538  u8state = COM_IDLE;
+
539  u16errCnt++;
+
540  return i8state;
+
541  }
+
542 
+
543  // validate message: id, CRC, FCT, exception
+
544  uint8_t u8exception = validateAnswer();
+
545  if (u8exception != 0) {
+
546  u8state = COM_IDLE;
+
547  return u8exception;
+
548  }
+
549 
+
550  // process answer
+
551  switch( au8Buffer[ FUNC ] ) {
+
552  case MB_FC_READ_COILS:
+ +
554  // call get_FC1 to transfer the incoming message to au16regs buffer
+
555  get_FC1( );
+
556  break;
+ +
558  case MB_FC_READ_REGISTERS :
+
559  // call get_FC3 to transfer the incoming message to au16regs buffer
+
560  get_FC3( );
+
561  break;
+
562  case MB_FC_WRITE_COIL:
+
563  case MB_FC_WRITE_REGISTER :
+ + +
566  // nothing to do
+
567  break;
+
568  default:
+
569  break;
+
570  }
+
571  u8state = COM_IDLE;
+
572  return u8BufferSize;
+
573 }
+
574 
+
588 int8_t Modbus::poll( uint16_t *regs, uint8_t u8size ) {
+
589 
+
590  au16regs = regs;
+
591  u8regsize = u8size;
+
592 
+
593  // check if there is any incoming frame
+
594  uint8_t u8current = port->available();
+
595  if (u8current == 0) return 0;
+
596 
+
597  // check T35 after frame end or still no frame end
+
598  if (u8current != u8lastRec) {
+
599  u8lastRec = u8current;
+
600  u32time = millis() + T35;
+
601  return 0;
+
602  }
+
603  if (millis() < u32time) return 0;
+
604 
+
605  u8lastRec = 0;
+
606  int8_t i8state = getRxBuffer();
+
607  u8lastError = i8state;
+
608  if (i8state < 7) return i8state;
+
609 
+
610  // check slave id
+
611  if (au8Buffer[ ID ] != u8id) return 0;
+
612 
+
613  // validate message: CRC, FCT, address and size
+
614  uint8_t u8exception = validateRequest();
+
615  if (u8exception > 0) {
+
616  if (u8exception != NO_REPLY) {
+
617  buildException( u8exception );
+
618  sendTxBuffer();
+
619  }
+
620  u8lastError = u8exception;
+
621  return u8exception;
+
622  }
+
623 
+
624  u32timeOut = millis() + long(u16timeOut);
+
625  u8lastError = 0;
+
626 
+
627  // process message
+
628  switch( au8Buffer[ FUNC ] ) {
+
629  case MB_FC_READ_COILS:
+ +
631  return process_FC1( regs, u8size );
+
632  break;
+ +
634  case MB_FC_READ_REGISTERS :
+
635  return process_FC3( regs, u8size );
+
636  break;
+
637  case MB_FC_WRITE_COIL:
+
638  return process_FC5( regs, u8size );
+
639  break;
+
640  case MB_FC_WRITE_REGISTER :
+
641  return process_FC6( regs, u8size );
+
642  break;
+ +
644  return process_FC15( regs, u8size );
+
645  break;
+ +
647  return process_FC16( regs, u8size );
+
648  break;
+
649  default:
+
650  break;
+
651  }
+
652  return i8state;
+
653 }
+
654 
+
655 /* _____PRIVATE FUNCTIONS_____________________________________________________ */
+
656 
+
657 void Modbus::init(uint8_t u8id, uint8_t u8serno, uint8_t u8txenpin) {
+
658  this->u8id = u8id;
+
659  this->u8serno = (u8serno > 3) ? 0 : u8serno;
+
660  this->u8txenpin = u8txenpin;
+
661  this->u16timeOut = 1000;
+
662 }
+
663 
+
671 int8_t Modbus::getRxBuffer() {
+
672  boolean bBuffOverflow = false;
+
673 
+
674  if (u8txenpin > 1) digitalWrite( u8txenpin, LOW );
+
675 
+
676  u8BufferSize = 0;
+
677  while ( port->available() ) {
+
678  au8Buffer[ u8BufferSize ] = port->read();
+
679  u8BufferSize ++;
+
680 
+
681  if (u8BufferSize >= MAX_BUFFER) bBuffOverflow = true;
+
682  }
+
683  u16InCnt++;
+
684 
+
685  if (bBuffOverflow) {
+
686  u16errCnt++;
+
687  return ERR_BUFF_OVERFLOW;
+
688  }
+
689  return u8BufferSize;
+
690 }
+
691 
+
704 void Modbus::sendTxBuffer() {
+
705  uint8_t i = 0;
+
706 
+
707  // append CRC to message
+
708  uint16_t u16crc = calcCRC( u8BufferSize );
+
709  au8Buffer[ u8BufferSize ] = u16crc >> 8;
+
710  u8BufferSize++;
+
711  au8Buffer[ u8BufferSize ] = u16crc & 0x00ff;
+
712  u8BufferSize++;
+
713 
+
714  // set RS485 transceiver to transmit mode
+
715  if (u8txenpin > 1) {
+
716  switch( u8serno ) {
+
717 #if defined(UBRR1H)
+
718  case 1:
+
719  UCSR1A=UCSR1A |(1 << TXC1);
+
720  break;
+
721 #endif
+
722 
+
723 #if defined(UBRR2H)
+
724  case 2:
+
725  UCSR2A=UCSR2A |(1 << TXC2);
+
726  break;
+
727 #endif
+
728 
+
729 #if defined(UBRR3H)
+
730  case 3:
+
731  UCSR3A=UCSR3A |(1 << TXC3);
+
732  break;
+
733 #endif
+
734  case 0:
+
735  default:
+
736  UCSR0A=UCSR0A |(1 << TXC0);
+
737  break;
+
738  }
+
739  digitalWrite( u8txenpin, HIGH );
+
740  }
+
741 
+
742  // transfer buffer to serial line
+
743  port->write( au8Buffer, u8BufferSize );
+
744 
+
745  // keep RS485 transceiver in transmit mode as long as sending
+
746  if (u8txenpin > 1) {
+
747  switch( u8serno ) {
+
748 #if defined(UBRR1H)
+
749  case 1:
+
750  while (!(UCSR1A & (1 << TXC1)));
+
751  break;
+
752 #endif
+
753 
+
754 #if defined(UBRR2H)
+
755  case 2:
+
756  while (!(UCSR2A & (1 << TXC2)));
+
757  break;
+
758 #endif
+
759 
+
760 #if defined(UBRR3H)
+
761  case 3:
+
762  while (!(UCSR3A & (1 << TXC3)));
+
763  break;
+
764 #endif
+
765  case 0:
+
766  default:
+
767  while (!(UCSR0A & (1 << TXC0)));
+
768  break;
+
769  }
+
770 
+
771  // return RS485 transceiver to receive mode
+
772  digitalWrite( u8txenpin, LOW );
+
773  }
+
774  port->flush();
+
775  u8BufferSize = 0;
+
776 
+
777  // set time-out for master
+
778  u32timeOut = millis() + (unsigned long) u16timeOut;
+
779 
+
780  // increase message counter
+
781  u16OutCnt++;
+
782 }
+
783 
+
791 uint16_t Modbus::calcCRC(uint8_t u8length) {
+
792  unsigned int temp, temp2, flag;
+
793  temp = 0xFFFF;
+
794  for (unsigned char i = 0; i < u8length; i++) {
+
795  temp = temp ^ au8Buffer[i];
+
796  for (unsigned char j = 1; j <= 8; j++) {
+
797  flag = temp & 0x0001;
+
798  temp >>=1;
+
799  if (flag)
+
800  temp ^= 0xA001;
+
801  }
+
802  }
+
803  // Reverse byte order.
+
804  temp2 = temp >> 8;
+
805  temp = (temp << 8) | temp2;
+
806  temp &= 0xFFFF;
+
807  // the returned value is already swapped
+
808  // crcLo byte is first & crcHi byte is last
+
809  return temp;
+
810 }
+
811 
+
819 uint8_t Modbus::validateRequest() {
+
820  // check message crc vs calculated crc
+
821  uint16_t u16MsgCRC =
+
822  ((au8Buffer[u8BufferSize - 2] << 8)
+
823  | au8Buffer[u8BufferSize - 1]); // combine the crc Low & High bytes
+
824  if ( calcCRC( u8BufferSize-2 ) != u16MsgCRC ) {
+
825  u16errCnt ++;
+
826  return NO_REPLY;
+
827  }
+
828 
+
829  // check fct code
+
830  boolean isSupported = false;
+
831  for (uint8_t i = 0; i< sizeof( fctsupported ); i++) {
+
832  if (fctsupported[i] == au8Buffer[FUNC]) {
+
833  isSupported = 1;
+
834  break;
+
835  }
+
836  }
+
837  if (!isSupported) {
+
838  u16errCnt ++;
+
839  return EXC_FUNC_CODE;
+
840  }
+
841 
+
842  // check start address & nb range
+
843  uint16_t u16regs = 0;
+
844  uint8_t u8regs;
+
845  switch ( au8Buffer[ FUNC ] ) {
+
846  case MB_FC_READ_COILS:
+ + +
849  u16regs = word( au8Buffer[ ADD_HI ], au8Buffer[ ADD_LO ]) / 16;
+
850  u16regs += word( au8Buffer[ NB_HI ], au8Buffer[ NB_LO ]) /16;
+
851  u8regs = (uint8_t) u16regs;
+
852  if (u8regs > u8regsize) return EXC_ADDR_RANGE;
+
853  break;
+
854  case MB_FC_WRITE_COIL:
+
855  u16regs = word( au8Buffer[ ADD_HI ], au8Buffer[ ADD_LO ]) / 16;
+
856  u8regs = (uint8_t) u16regs;
+
857  if (u8regs > u8regsize) return EXC_ADDR_RANGE;
+
858  break;
+
859  case MB_FC_WRITE_REGISTER :
+
860  u16regs = word( au8Buffer[ ADD_HI ], au8Buffer[ ADD_LO ]);
+
861  u8regs = (uint8_t) u16regs;
+
862  if (u8regs > u8regsize) return EXC_ADDR_RANGE;
+
863  break;
+
864  case MB_FC_READ_REGISTERS :
+ + +
867  u16regs = word( au8Buffer[ ADD_HI ], au8Buffer[ ADD_LO ]);
+
868  u16regs += word( au8Buffer[ NB_HI ], au8Buffer[ NB_LO ]);
+
869  u8regs = (uint8_t) u16regs;
+
870  if (u8regs > u8regsize) return EXC_ADDR_RANGE;
+
871  break;
+
872  }
+
873  return 0; // OK, no exception code thrown
+
874 }
+
875 
+
883 uint8_t Modbus::validateAnswer() {
+
884  // check message crc vs calculated crc
+
885  uint16_t u16MsgCRC =
+
886  ((au8Buffer[u8BufferSize - 2] << 8)
+
887  | au8Buffer[u8BufferSize - 1]); // combine the crc Low & High bytes
+
888  if ( calcCRC( u8BufferSize-2 ) != u16MsgCRC ) {
+
889  u16errCnt ++;
+
890  return NO_REPLY;
+
891  }
+
892 
+
893  // check exception
+
894  if ((au8Buffer[ FUNC ] & 0x80) != 0) {
+
895  u16errCnt ++;
+
896  return ERR_EXCEPTION;
+
897  }
+
898 
+
899  // check fct code
+
900  boolean isSupported = false;
+
901  for (uint8_t i = 0; i< sizeof( fctsupported ); i++) {
+
902  if (fctsupported[i] == au8Buffer[FUNC]) {
+
903  isSupported = 1;
+
904  break;
+
905  }
+
906  }
+
907  if (!isSupported) {
+
908  u16errCnt ++;
+
909  return EXC_FUNC_CODE;
+
910  }
+
911 
+
912  return 0; // OK, no exception code thrown
+
913 }
+
914 
+
921 void Modbus::buildException( uint8_t u8exception ) {
+
922  uint8_t u8func = au8Buffer[ FUNC ]; // get the original FUNC code
+
923 
+
924  au8Buffer[ ID ] = u8id;
+
925  au8Buffer[ FUNC ] = u8func + 0x80;
+
926  au8Buffer[ 2 ] = u8exception;
+
927  u8BufferSize = EXCEPTION_SIZE;
+
928 }
+
929 
+
936 void Modbus::get_FC1() {
+
937  uint8_t u8byte, i;
+
938  u8byte = 0;
+
939 
+
940  // for (i=0; i< au8Buffer[ 2 ] /2; i++) {
+
941  // au16regs[ i ] = word(
+
942  // au8Buffer[ u8byte ],
+
943  // au8Buffer[ u8byte +1 ]);
+
944  // u8byte += 2;
+
945  // }
+
946 }
+
947 
+
954 void Modbus::get_FC3() {
+
955  uint8_t u8byte, i;
+
956  u8byte = 3;
+
957 
+
958  for (i=0; i< au8Buffer[ 2 ] /2; i++) {
+
959  au16regs[ i ] = word(
+
960  au8Buffer[ u8byte ],
+
961  au8Buffer[ u8byte +1 ]);
+
962  u8byte += 2;
+
963  }
+
964 }
+
965 
+
974 int8_t Modbus::process_FC1( uint16_t *regs, uint8_t u8size ) {
+
975  uint8_t u8currentRegister, u8currentBit, u8bytesno, u8bitsno;
+
976  uint8_t u8CopyBufferSize;
+
977  uint16_t u16currentCoil, u16coil;
+
978 
+
979  // get the first and last coil from the message
+
980  uint16_t u16StartCoil = word( au8Buffer[ ADD_HI ], au8Buffer[ ADD_LO ] );
+
981  uint16_t u16Coilno = word( au8Buffer[ NB_HI ], au8Buffer[ NB_LO ] );
+
982 
+
983  // put the number of bytes in the outcoming message
+
984  u8bytesno = (uint8_t) (u16Coilno / 8);
+
985  if (u16Coilno % 8 != 0) u8bytesno ++;
+
986  au8Buffer[ ADD_HI ] = u8bytesno;
+
987  u8BufferSize = ADD_LO;
+
988 
+
989  // read each coil from the register map and put its value inside the outcoming message
+
990  u8bitsno = 0;
+
991 
+
992  for (u16currentCoil = 0; u16currentCoil < u16Coilno; u16currentCoil++) {
+
993  u16coil = u16StartCoil + u16currentCoil;
+
994  u8currentRegister = (uint8_t) (u16coil / 16);
+
995  u8currentBit = (uint8_t) (u16coil % 16);
+
996 
+
997  bitWrite(
+
998  au8Buffer[ u8BufferSize ],
+
999  u8bitsno,
+
1000  bitRead( regs[ u8currentRegister ], u8currentBit ) );
+
1001  u8bitsno ++;
+
1002 
+
1003  if (u8bitsno > 7) {
+
1004  u8bitsno = 0;
+
1005  u8BufferSize++;
+
1006  }
+
1007  }
+
1008 
+
1009  // send outcoming message
+
1010  if (u16Coilno % 8 != 0) u8BufferSize ++;
+
1011  u8CopyBufferSize = u8BufferSize +2;
+
1012  sendTxBuffer();
+
1013  return u8CopyBufferSize;
+
1014 }
+
1015 
+
1024 int8_t Modbus::process_FC3( uint16_t *regs, uint8_t u8size ) {
+
1025 
+
1026  uint8_t u8StartAdd = word( au8Buffer[ ADD_HI ], au8Buffer[ ADD_LO ] );
+
1027  uint8_t u8regsno = word( au8Buffer[ NB_HI ], au8Buffer[ NB_LO ] );
+
1028  uint8_t u8CopyBufferSize;
+
1029  uint8_t i;
+
1030 
+
1031  au8Buffer[ 2 ] = u8regsno * 2;
+
1032  u8BufferSize = 3;
+
1033 
+
1034  for (i = u8StartAdd; i < u8StartAdd + u8regsno; i++) {
+
1035  au8Buffer[ u8BufferSize ] = highByte(regs[i]);
+
1036  u8BufferSize++;
+
1037  au8Buffer[ u8BufferSize ] = lowByte(regs[i]);
+
1038  u8BufferSize++;
+
1039  }
+
1040  u8CopyBufferSize = u8BufferSize +2;
+
1041  sendTxBuffer();
+
1042 
+
1043  return u8CopyBufferSize;
+
1044 }
+
1045 
+
1054 int8_t Modbus::process_FC5( uint16_t *regs, uint8_t u8size ) {
+
1055  uint8_t u8currentRegister, u8currentBit;
+
1056  uint8_t u8CopyBufferSize;
+
1057  uint16_t u16coil = word( au8Buffer[ ADD_HI ], au8Buffer[ ADD_LO ] );
+
1058 
+
1059  // point to the register and its bit
+
1060  u8currentRegister = (uint8_t) (u16coil / 16);
+
1061  u8currentBit = (uint8_t) (u16coil % 16);
+
1062 
+
1063  // write to coil
+
1064  bitWrite(
+
1065  regs[ u8currentRegister ],
+
1066  u8currentBit,
+
1067  au8Buffer[ NB_HI ] == 0xff );
+
1068 
+
1069 
+
1070  // send answer to master
+
1071  u8BufferSize = 6;
+
1072  u8CopyBufferSize = u8BufferSize +2;
+
1073  sendTxBuffer();
+
1074 
+
1075  return u8CopyBufferSize;
+
1076 }
+
1077 
+
1086 int8_t Modbus::process_FC6( uint16_t *regs, uint8_t u8size ) {
+
1087 
+
1088  uint8_t u8add = word( au8Buffer[ ADD_HI ], au8Buffer[ ADD_LO ] );
+
1089  uint8_t u8CopyBufferSize;
+
1090  uint16_t u16val = word( au8Buffer[ NB_HI ], au8Buffer[ NB_LO ] );
+
1091 
+
1092  regs[ u8add ] = u16val;
+
1093 
+
1094  // keep the same header
+
1095  u8BufferSize = RESPONSE_SIZE;
+
1096 
+
1097  u8CopyBufferSize = u8BufferSize +2;
+
1098  sendTxBuffer();
+
1099 
+
1100  return u8CopyBufferSize;
+
1101 }
+
1102 
+
1111 int8_t Modbus::process_FC15( uint16_t *regs, uint8_t u8size ) {
+
1112  uint8_t u8currentRegister, u8currentBit, u8frameByte, u8bitsno;
+
1113  uint8_t u8CopyBufferSize;
+
1114  uint16_t u16currentCoil, u16coil;
+
1115  boolean bTemp;
+
1116 
+
1117  // get the first and last coil from the message
+
1118  uint16_t u16StartCoil = word( au8Buffer[ ADD_HI ], au8Buffer[ ADD_LO ] );
+
1119  uint16_t u16Coilno = word( au8Buffer[ NB_HI ], au8Buffer[ NB_LO ] );
+
1120 
+
1121 
+
1122  // read each coil from the register map and put its value inside the outcoming message
+
1123  u8bitsno = 0;
+
1124  u8frameByte = 7;
+
1125  for (u16currentCoil = 0; u16currentCoil < u16Coilno; u16currentCoil++) {
+
1126 
+
1127  u16coil = u16StartCoil + u16currentCoil;
+
1128  u8currentRegister = (uint8_t) (u16coil / 16);
+
1129  u8currentBit = (uint8_t) (u16coil % 16);
+
1130 
+
1131  bTemp = bitRead(
+
1132  au8Buffer[ u8frameByte ],
+
1133  u8bitsno );
+
1134 
+
1135  bitWrite(
+
1136  regs[ u8currentRegister ],
+
1137  u8currentBit,
+
1138  bTemp );
+
1139 
+
1140  u8bitsno ++;
+
1141 
+
1142  if (u8bitsno > 7) {
+
1143  u8bitsno = 0;
+
1144  u8frameByte++;
+
1145  }
+
1146  }
+
1147 
+
1148  // send outcoming message
+
1149  // it's just a copy of the incomping frame until 6th byte
+
1150  u8BufferSize = 6;
+
1151  u8CopyBufferSize = u8BufferSize +2;
+
1152  sendTxBuffer();
+
1153  return u8CopyBufferSize;
+
1154 }
+
1155 
+
1164 int8_t Modbus::process_FC16( uint16_t *regs, uint8_t u8size ) {
+
1165  uint8_t u8func = au8Buffer[ FUNC ]; // get the original FUNC code
+
1166  uint8_t u8StartAdd = au8Buffer[ ADD_HI ] << 8 | au8Buffer[ ADD_LO ];
+
1167  uint8_t u8regsno = au8Buffer[ NB_HI ] << 8 | au8Buffer[ NB_LO ];
+
1168  uint8_t u8CopyBufferSize;
+
1169  uint8_t i;
+
1170  uint16_t temp;
+
1171 
+
1172  // build header
+
1173  au8Buffer[ NB_HI ] = 0;
+
1174  au8Buffer[ NB_LO ] = u8regsno;
+
1175  u8BufferSize = RESPONSE_SIZE;
+
1176 
+
1177  // write registers
+
1178  for (i = 0; i < u8regsno; i++) {
+
1179  temp = word(
+
1180  au8Buffer[ (BYTE_CNT + 1) + i * 2 ],
+
1181  au8Buffer[ (BYTE_CNT + 2) + i * 2 ]);
+
1182 
+
1183  regs[ u8StartAdd + i ] = temp;
+
1184  }
+
1185  u8CopyBufferSize = u8BufferSize +2;
+
1186  sendTxBuffer();
+
1187 
+
1188  return u8CopyBufferSize;
+
1189 }
+
+ + + + diff --git a/software/firmware/libraries/modbus/documentation/html/annotated.html b/software/firmware/libraries/modbus/documentation/html/annotated.html new file mode 100644 index 0000000..c3eefd7 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/html/annotated.html @@ -0,0 +1,67 @@ + + + + + + +Modbus Master and Slave for Arduino: Class List + + + + + + +
+
+ + + + + + +
+
Modbus Master and Slave for Arduino +  1.2 +
+
Arduino library for implementing a Modbus Master or Slave through Serial port
+
+
+ + + + +
+
+
+
Class List
+
+
+
Here are the classes, structs, unions and interfaces with brief descriptions:
+ + + +
oCModbusArduino class library for communicating with Modbus devices over USB/RS232/485 (via RTU protocol)
\Cmodbus_tMaster query structure: This includes all the necessary fields to make the Master generate a Modbus query. A Master may keep several of these structures and send them cyclically or use them according to program needs
+
+
+ + + + diff --git a/software/firmware/libraries/modbus/documentation/html/class_modbus-members.html b/software/firmware/libraries/modbus/documentation/html/class_modbus-members.html new file mode 100644 index 0000000..9a8519b --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/html/class_modbus-members.html @@ -0,0 +1,83 @@ + + + + + + +Modbus Master and Slave for Arduino: Member List + + + + + + +
+
+ + + + + + +
+
Modbus Master and Slave for Arduino +  1.2 +
+
Arduino library for implementing a Modbus Master or Slave through Serial port
+
+
+ + + + +
+
+
+
Modbus Member List
+
+
+ +

This is the complete list of members for Modbus, including all inherited members.

+ + + + + + + + + + + + + + + + + + + + +
begin(long u32speed)Modbus
begin()Modbus
end()Modbus
getErrCnt()Modbus
getID()Modbus
getInCnt()Modbus
getLastError()Modbus
getOutCnt()Modbus
getState()Modbus
getTimeOut()Modbus
getTimeOutState()Modbus
Modbus()Modbus
Modbus(uint8_t u8id, uint8_t u8serno)Modbus
Modbus(uint8_t u8id, uint8_t u8serno, uint8_t u8txenpin)Modbus
poll()Modbus
poll(uint16_t *regs, uint8_t u8size)Modbus
query(modbus_t telegram)Modbus
setID(uint8_t u8id)Modbus
setTimeOut(uint16_t u16timeout)Modbus
+ + + + diff --git a/software/firmware/libraries/modbus/documentation/html/class_modbus.html b/software/firmware/libraries/modbus/documentation/html/class_modbus.html new file mode 100644 index 0000000..3ec771f --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/html/class_modbus.html @@ -0,0 +1,248 @@ + + + + + + +Modbus Master and Slave for Arduino: Modbus Class Reference + + + + + + +
+
+ + + + + + +
+
Modbus Master and Slave for Arduino +  1.2 +
+
Arduino library for implementing a Modbus Master or Slave through Serial port
+
+
+ + + + +
+
+ +
+
Modbus Class Reference
+
+
+ +

Arduino class library for communicating with Modbus devices over USB/RS232/485 (via RTU protocol). + More...

+ +

#include <ModbusRtu.h>

+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

 Modbus ()
 Default Constructor for Master through Serial. More...
 
 Modbus (uint8_t u8id, uint8_t u8serno)
 
 Modbus (uint8_t u8id, uint8_t u8serno, uint8_t u8txenpin)
 
void begin (long u32speed)
 Initialize class object. More...
 
void begin ()
 
void setTimeOut (uint16_t u16timeout)
 write communication watch-dog timer More...
 
uint16_t getTimeOut ()
 get communication watch-dog timer value More...
 
boolean getTimeOutState ()
 get communication watch-dog timer state More...
 
int8_t query (modbus_t telegram)
 only for master More...
 
int8_t poll ()
 cyclic poll for master More...
 
int8_t poll (uint16_t *regs, uint8_t u8size)
 cyclic poll for slave More...
 
uint16_t getInCnt ()
 number of incoming messages More...
 
uint16_t getOutCnt ()
 number of outcoming messages More...
 
uint16_t getErrCnt ()
 error counter More...
 
uint8_t getID ()
 get slave ID between 1 and 247 More...
 
uint8_t getState ()
 
uint8_t getLastError ()
 get last error message More...
 
void setID (uint8_t u8id)
 write new ID for the slave More...
 
void end ()
 finish any communication and release serial communication port More...
 
+

Detailed Description

+

Arduino class library for communicating with Modbus devices over USB/RS232/485 (via RTU protocol).

+ +

Definition at line 141 of file ModbusRtu.h.

+

Constructor & Destructor Documentation

+ +
+
+ + + + + + + + + + + + + + + + + + +
Modbus::Modbus (uint8_t u8id,
uint8_t u8serno 
)
+
+ +

Definition at line 218 of file ModbusRtu.h.

+ +
+
+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + +
Modbus::Modbus (uint8_t u8id,
uint8_t u8serno,
uint8_t u8txenpin 
)
+
+ +

Definition at line 234 of file ModbusRtu.h.

+ +
+
+

Member Function Documentation

+ +
+
+ + + + + + + +
void Modbus::begin ()
+
+ +

Definition at line 299 of file ModbusRtu.h.

+ +
+
+ +
+
+ + + + + + + +
void Modbus::end ()
+
+ +

finish any communication and release serial communication port

+ +
+
+ +
+
+ + + + + + + +
uint16_t Modbus::getTimeOut ()
+
+ +

get communication watch-dog timer value

+ +
+
+
The documentation for this class was generated from the following file: +
+ + + + diff --git a/software/firmware/libraries/modbus/documentation/html/classes.html b/software/firmware/libraries/modbus/documentation/html/classes.html new file mode 100644 index 0000000..65da245 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/html/classes.html @@ -0,0 +1,70 @@ + + + + + + +Modbus Master and Slave for Arduino: Class Index + + + + + + +
+
+ + + + + + +
+
Modbus Master and Slave for Arduino +  1.2 +
+
Arduino library for implementing a Modbus Master or Slave through Serial port
+
+
+ + + + +
+
+
+
Class Index
+
+
+ + + + + + +
  M  
+
modbus_t   
Modbus   
+ +
+ + + + diff --git a/software/firmware/libraries/modbus/documentation/html/doxygen.css b/software/firmware/libraries/modbus/documentation/html/doxygen.css new file mode 100644 index 0000000..3ac2851 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/html/doxygen.css @@ -0,0 +1,1186 @@ +/* The standard CSS for doxygen 1.8.4 */ + +body, table, div, p, dl { + font: 400 14px/22px Roboto,sans-serif; +} + +/* @group Heading Levels */ + +h1.groupheader { + font-size: 150%; +} + +.title { + font: 400 14px/28px Roboto,sans-serif; + font-size: 150%; + font-weight: bold; + margin: 10px 2px; +} + +h2.groupheader { + border-bottom: 1px solid #879ECB; + color: #354C7B; + font-size: 150%; + font-weight: normal; + margin-top: 1.75em; + padding-top: 8px; + padding-bottom: 4px; + width: 100%; +} + +h3.groupheader { + font-size: 100%; +} + +h1, h2, h3, h4, h5, h6 { + -webkit-transition: text-shadow 0.5s linear; + -moz-transition: text-shadow 0.5s linear; + -ms-transition: text-shadow 0.5s linear; + -o-transition: text-shadow 0.5s linear; + transition: text-shadow 0.5s linear; + margin-right: 15px; +} + +h1.glow, h2.glow, h3.glow, h4.glow, h5.glow, h6.glow { + text-shadow: 0 0 15px cyan; +} + +dt { + font-weight: bold; +} + +div.multicol { + -moz-column-gap: 1em; + -webkit-column-gap: 1em; + -moz-column-count: 3; + -webkit-column-count: 3; +} + +p.startli, p.startdd, p.starttd { + margin-top: 2px; +} + +p.endli { + margin-bottom: 0px; +} + +p.enddd { + margin-bottom: 4px; +} + +p.endtd { + margin-bottom: 2px; +} + +/* @end */ + +caption { + font-weight: bold; +} + +span.legend { + font-size: 70%; + text-align: center; +} + +h3.version { + font-size: 90%; + text-align: center; +} + +div.qindex, div.navtab{ + background-color: #EBEFF6; + border: 1px solid #A3B4D7; + text-align: center; +} + +div.qindex, div.navpath { + width: 100%; + line-height: 140%; +} + +div.navtab { + margin-right: 15px; +} + +/* @group Link Styling */ + +a { + color: #3D578C; + font-weight: normal; + text-decoration: none; +} + +.contents a:visited { + color: #4665A2; +} + +a:hover { + text-decoration: underline; +} + +a.qindex { + font-weight: bold; +} + +a.qindexHL { + font-weight: bold; + background-color: #9CAFD4; + color: #ffffff; + border: 1px double #869DCA; +} + +.contents a.qindexHL:visited { + color: #ffffff; +} + +a.el { + font-weight: bold; +} + +a.elRef { +} + +a.code, a.code:visited { + color: #4665A2; +} + +a.codeRef, a.codeRef:visited { + color: #4665A2; +} + +/* @end */ + +dl.el { + margin-left: -1cm; +} + +pre.fragment { + border: 1px solid #C4CFE5; + background-color: #FBFCFD; + padding: 4px 6px; + margin: 4px 8px 4px 2px; + overflow: auto; + word-wrap: break-word; + font-size: 9pt; + line-height: 125%; + font-family: monospace, fixed; + font-size: 105%; +} + +div.fragment { + padding: 0px; + margin: 0px; + background-color: #FBFCFD; + border: 1px solid #C4CFE5; +} + +div.line { + font-family: monospace, fixed; + font-size: 13px; + min-height: 13px; + line-height: 1.0; + text-wrap: unrestricted; + white-space: -moz-pre-wrap; /* Moz */ + white-space: -pre-wrap; /* Opera 4-6 */ + white-space: -o-pre-wrap; /* Opera 7 */ + white-space: pre-wrap; /* CSS3 */ + word-wrap: break-word; /* IE 5.5+ */ + text-indent: -53px; + padding-left: 53px; + padding-bottom: 0px; + margin: 0px; + -webkit-transition-property: background-color, box-shadow; + -webkit-transition-duration: 0.5s; + -moz-transition-property: background-color, box-shadow; + -moz-transition-duration: 0.5s; + -ms-transition-property: background-color, box-shadow; + -ms-transition-duration: 0.5s; + -o-transition-property: background-color, box-shadow; + -o-transition-duration: 0.5s; + transition-property: background-color, box-shadow; + transition-duration: 0.5s; +} + +div.line.glow { + background-color: cyan; + box-shadow: 0 0 10px cyan; +} + + +span.lineno { + padding-right: 4px; + text-align: right; + border-right: 2px solid #0F0; + background-color: #E8E8E8; + white-space: pre; +} +span.lineno a { + background-color: #D8D8D8; +} + +span.lineno a:hover { + background-color: #C8C8C8; +} + +div.ah { + background-color: black; + font-weight: bold; + color: #ffffff; + margin-bottom: 3px; + margin-top: 3px; + padding: 0.2em; + border: solid thin #333; + border-radius: 0.5em; + -webkit-border-radius: .5em; + -moz-border-radius: .5em; + box-shadow: 2px 2px 3px #999; + -webkit-box-shadow: 2px 2px 3px #999; + -moz-box-shadow: rgba(0, 0, 0, 0.15) 2px 2px 2px; + background-image: -webkit-gradient(linear, left top, left bottom, from(#eee), to(#000),color-stop(0.3, #444)); + background-image: -moz-linear-gradient(center top, #eee 0%, #444 40%, #000); +} + +div.groupHeader { + margin-left: 16px; + margin-top: 12px; + font-weight: bold; +} + +div.groupText { + margin-left: 16px; + font-style: italic; +} + +body { + background-color: white; + color: black; + margin: 0; +} + +div.contents { + margin-top: 10px; + margin-left: 12px; + margin-right: 8px; +} + +td.indexkey { + background-color: #EBEFF6; + font-weight: bold; + border: 1px solid #C4CFE5; + margin: 2px 0px 2px 0; + padding: 2px 10px; + white-space: nowrap; + vertical-align: top; +} + +td.indexvalue { + background-color: #EBEFF6; + border: 1px solid #C4CFE5; + padding: 2px 10px; + margin: 2px 0px; +} + +tr.memlist { + background-color: #EEF1F7; +} + +p.formulaDsp { + text-align: center; +} + +img.formulaDsp { + +} + +img.formulaInl { + vertical-align: middle; +} + +div.center { + text-align: center; + margin-top: 0px; + margin-bottom: 0px; + padding: 0px; +} + +div.center img { + border: 0px; +} + +address.footer { + text-align: right; + padding-right: 12px; +} + +img.footer { + border: 0px; + vertical-align: middle; +} + +/* @group Code Colorization */ + +span.keyword { + color: #008000 +} + +span.keywordtype { + color: #604020 +} + +span.keywordflow { + color: #e08000 +} + +span.comment { + color: #800000 +} + +span.preprocessor { + color: #806020 +} + +span.stringliteral { + color: #002080 +} + +span.charliteral { + color: #008080 +} + +span.vhdldigit { + color: #ff00ff +} + +span.vhdlchar { + color: #000000 +} + +span.vhdlkeyword { + color: #700070 +} + +span.vhdllogic { + color: #ff0000 +} + +blockquote { + background-color: #F7F8FB; + border-left: 2px solid #9CAFD4; + margin: 0 24px 0 4px; + padding: 0 12px 0 16px; +} + +/* @end */ + +/* +.search { + color: #003399; + font-weight: bold; +} + +form.search { + margin-bottom: 0px; + margin-top: 0px; +} + +input.search { + font-size: 75%; + color: #000080; + font-weight: normal; + background-color: #e8eef2; +} +*/ + +td.tiny { + font-size: 75%; +} + +.dirtab { + padding: 4px; + border-collapse: collapse; + border: 1px solid #A3B4D7; +} + +th.dirtab { + background: #EBEFF6; + font-weight: bold; +} + +hr { + height: 0px; + border: none; + border-top: 1px solid #4A6AAA; +} + +hr.footer { + height: 1px; +} + +/* @group Member Descriptions */ + +table.memberdecls { + border-spacing: 0px; + padding: 0px; +} + +.memberdecls td, .fieldtable tr { + -webkit-transition-property: background-color, box-shadow; + -webkit-transition-duration: 0.5s; + -moz-transition-property: background-color, box-shadow; + -moz-transition-duration: 0.5s; + -ms-transition-property: background-color, box-shadow; + -ms-transition-duration: 0.5s; + -o-transition-property: background-color, box-shadow; + -o-transition-duration: 0.5s; + transition-property: background-color, box-shadow; + transition-duration: 0.5s; +} + +.memberdecls td.glow, .fieldtable tr.glow { + background-color: cyan; + box-shadow: 0 0 15px cyan; +} + +.mdescLeft, .mdescRight, +.memItemLeft, .memItemRight, +.memTemplItemLeft, .memTemplItemRight, .memTemplParams { + background-color: #F9FAFC; + border: none; + margin: 4px; + padding: 1px 0 0 8px; +} + +.mdescLeft, .mdescRight { + padding: 0px 8px 4px 8px; + color: #555; +} + +.memSeparator { + border-bottom: 1px solid #DEE4F0; + line-height: 1px; + margin: 0px; + padding: 0px; +} + +.memItemLeft, .memTemplItemLeft { + white-space: nowrap; +} + +.memItemRight { + width: 100%; +} + +.memTemplParams { + color: #4665A2; + white-space: nowrap; + font-size: 80%; +} + +/* @end */ + +/* @group Member Details */ + +/* Styles for detailed member documentation */ + +.memtemplate { + font-size: 80%; + color: #4665A2; + font-weight: normal; + margin-left: 9px; +} + +.memnav { + background-color: #EBEFF6; + border: 1px solid #A3B4D7; + text-align: center; + margin: 2px; + margin-right: 15px; + padding: 2px; +} + +.mempage { + width: 100%; +} + +.memitem { + padding: 0; + margin-bottom: 10px; + margin-right: 5px; + -webkit-transition: box-shadow 0.5s linear; + -moz-transition: box-shadow 0.5s linear; + -ms-transition: box-shadow 0.5s linear; + -o-transition: box-shadow 0.5s linear; + transition: box-shadow 0.5s linear; + display: table !important; + width: 100%; +} + +.memitem.glow { + box-shadow: 0 0 15px cyan; +} + +.memname { + font-weight: bold; + margin-left: 6px; +} + +.memname td { + vertical-align: bottom; +} + +.memproto, dl.reflist dt { + border-top: 1px solid #A8B8D9; + border-left: 1px solid #A8B8D9; + border-right: 1px solid #A8B8D9; + padding: 6px 0px 6px 0px; + color: #253555; + font-weight: bold; + text-shadow: 0px 1px 1px rgba(255, 255, 255, 0.9); + background-image:url('nav_f.png'); + background-repeat:repeat-x; + background-color: #E2E8F2; + /* opera specific markup */ + box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); + border-top-right-radius: 4px; + border-top-left-radius: 4px; + /* firefox specific markup */ + -moz-box-shadow: rgba(0, 0, 0, 0.15) 5px 5px 5px; + -moz-border-radius-topright: 4px; + -moz-border-radius-topleft: 4px; + /* webkit specific markup */ + -webkit-box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); + -webkit-border-top-right-radius: 4px; + -webkit-border-top-left-radius: 4px; + +} + +.memdoc, dl.reflist dd { + border-bottom: 1px solid #A8B8D9; + border-left: 1px solid #A8B8D9; + border-right: 1px solid #A8B8D9; + padding: 6px 10px 2px 10px; + background-color: #FBFCFD; + border-top-width: 0; + background-image:url('nav_g.png'); + background-repeat:repeat-x; + background-color: #FFFFFF; + /* opera specific markup */ + border-bottom-left-radius: 4px; + border-bottom-right-radius: 4px; + box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); + /* firefox specific markup */ + -moz-border-radius-bottomleft: 4px; + -moz-border-radius-bottomright: 4px; + -moz-box-shadow: rgba(0, 0, 0, 0.15) 5px 5px 5px; + /* webkit specific markup */ + -webkit-border-bottom-left-radius: 4px; + -webkit-border-bottom-right-radius: 4px; + -webkit-box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); +} + +dl.reflist dt { + padding: 5px; +} + +dl.reflist dd { + margin: 0px 0px 10px 0px; + padding: 5px; +} + +.paramkey { + text-align: right; +} + +.paramtype { + white-space: nowrap; +} + +.paramname { + color: #602020; + white-space: nowrap; +} +.paramname em { + font-style: normal; +} +.paramname code { + line-height: 14px; +} + +.params, .retval, .exception, .tparams { + margin-left: 0px; + padding-left: 0px; +} + +.params .paramname, .retval .paramname { + font-weight: bold; + vertical-align: top; +} + +.params .paramtype { + font-style: italic; + vertical-align: top; +} + +.params .paramdir { + font-family: "courier new",courier,monospace; + vertical-align: top; +} + +table.mlabels { + border-spacing: 0px; +} + +td.mlabels-left { + width: 100%; + padding: 0px; +} + +td.mlabels-right { + vertical-align: bottom; + padding: 0px; + white-space: nowrap; +} + +span.mlabels { + margin-left: 8px; +} + +span.mlabel { + background-color: #728DC1; + border-top:1px solid #5373B4; + border-left:1px solid #5373B4; + border-right:1px solid #C4CFE5; + border-bottom:1px solid #C4CFE5; + text-shadow: none; + color: white; + margin-right: 4px; + padding: 2px 3px; + border-radius: 3px; + font-size: 7pt; + white-space: nowrap; + vertical-align: middle; +} + + + +/* @end */ + +/* these are for tree view when not used as main index */ + +div.directory { + margin: 10px 0px; + border-top: 1px solid #A8B8D9; + border-bottom: 1px solid #A8B8D9; + width: 100%; +} + +.directory table { + border-collapse:collapse; +} + +.directory td { + margin: 0px; + padding: 0px; + vertical-align: top; +} + +.directory td.entry { + white-space: nowrap; + padding-right: 6px; + padding-top: 3px; +} + +.directory td.entry a { + outline:none; +} + +.directory td.entry a img { + border: none; +} + +.directory td.desc { + width: 100%; + padding-left: 6px; + padding-right: 6px; + padding-top: 3px; + border-left: 1px solid rgba(0,0,0,0.05); +} + +.directory tr.even { + padding-left: 6px; + background-color: #F7F8FB; +} + +.directory img { + vertical-align: -30%; +} + +.directory .levels { + white-space: nowrap; + width: 100%; + text-align: right; + font-size: 9pt; +} + +.directory .levels span { + cursor: pointer; + padding-left: 2px; + padding-right: 2px; + color: #3D578C; +} + +div.dynheader { + margin-top: 8px; + -webkit-touch-callout: none; + -webkit-user-select: none; + -khtml-user-select: none; + -moz-user-select: none; + -ms-user-select: none; + user-select: none; +} + +address { + font-style: normal; + color: #2A3D61; +} + +table.doxtable { + border-collapse:collapse; + margin-top: 4px; + margin-bottom: 4px; +} + +table.doxtable td, table.doxtable th { + border: 1px solid #2D4068; + padding: 3px 7px 2px; +} + +table.doxtable th { + background-color: #374F7F; + color: #FFFFFF; + font-size: 110%; + padding-bottom: 4px; + padding-top: 5px; +} + +table.fieldtable { + /*width: 100%;*/ + margin-bottom: 10px; + border: 1px solid #A8B8D9; + border-spacing: 0px; + -moz-border-radius: 4px; + -webkit-border-radius: 4px; + border-radius: 4px; + -moz-box-shadow: rgba(0, 0, 0, 0.15) 2px 2px 2px; + -webkit-box-shadow: 2px 2px 2px rgba(0, 0, 0, 0.15); + box-shadow: 2px 2px 2px rgba(0, 0, 0, 0.15); +} + +.fieldtable td, .fieldtable th { + padding: 3px 7px 2px; +} + +.fieldtable td.fieldtype, .fieldtable td.fieldname { + white-space: nowrap; + border-right: 1px solid #A8B8D9; + border-bottom: 1px solid #A8B8D9; + vertical-align: top; +} + +.fieldtable td.fieldname { + padding-top: 3px; +} + +.fieldtable td.fielddoc { + border-bottom: 1px solid #A8B8D9; + /*width: 100%;*/ +} + +.fieldtable td.fielddoc p:first-child { + margin-top: 0px; +} + +.fieldtable td.fielddoc p:last-child { + margin-bottom: 2px; +} + +.fieldtable tr:last-child td { + border-bottom: none; +} + +.fieldtable th { + background-image:url('nav_f.png'); + background-repeat:repeat-x; + background-color: #E2E8F2; + font-size: 90%; + color: #253555; + padding-bottom: 4px; + padding-top: 5px; + text-align:left; + -moz-border-radius-topleft: 4px; + -moz-border-radius-topright: 4px; + -webkit-border-top-left-radius: 4px; + -webkit-border-top-right-radius: 4px; + border-top-left-radius: 4px; + border-top-right-radius: 4px; + border-bottom: 1px solid #A8B8D9; +} + + +.tabsearch { + top: 0px; + left: 10px; + height: 36px; + background-image: url('tab_b.png'); + z-index: 101; + overflow: hidden; + font-size: 13px; +} + +.navpath ul +{ + font-size: 11px; + background-image:url('tab_b.png'); + background-repeat:repeat-x; + background-position: 0 -5px; + height:30px; + line-height:30px; + color:#8AA0CC; + border:solid 1px #C2CDE4; + overflow:hidden; + margin:0px; + padding:0px; +} + +.navpath li +{ + list-style-type:none; + float:left; + padding-left:10px; + padding-right:15px; + background-image:url('bc_s.png'); + background-repeat:no-repeat; + background-position:right; + color:#364D7C; +} + +.navpath li.navelem a +{ + height:32px; + display:block; + text-decoration: none; + outline: none; + color: #283A5D; + font-family: 'Lucida Grande',Geneva,Helvetica,Arial,sans-serif; + text-shadow: 0px 1px 1px rgba(255, 255, 255, 0.9); + text-decoration: none; +} + +.navpath li.navelem a:hover +{ + color:#6884BD; +} + +.navpath li.footer +{ + list-style-type:none; + float:right; + padding-left:10px; + padding-right:15px; + background-image:none; + background-repeat:no-repeat; + background-position:right; + color:#364D7C; + font-size: 8pt; +} + + +div.summary +{ + float: right; + font-size: 8pt; + padding-right: 5px; + width: 50%; + text-align: right; +} + +div.summary a +{ + white-space: nowrap; +} + +div.ingroups +{ + font-size: 8pt; + width: 50%; + text-align: left; +} + +div.ingroups a +{ + white-space: nowrap; +} + +div.header +{ + background-image:url('nav_h.png'); + background-repeat:repeat-x; + background-color: #F9FAFC; + margin: 0px; + border-bottom: 1px solid #C4CFE5; +} + +div.headertitle +{ + padding: 5px 5px 5px 10px; +} + +dl +{ + padding: 0 0 0 10px; +} + +/* dl.note, dl.warning, dl.attention, dl.pre, dl.post, dl.invariant, dl.deprecated, dl.todo, dl.test, dl.bug */ +dl.section +{ + margin-left: 0px; + padding-left: 0px; +} + +dl.note +{ + margin-left:-7px; + padding-left: 3px; + border-left:4px solid; + border-color: #D0C000; +} + +dl.warning, dl.attention +{ + margin-left:-7px; + padding-left: 3px; + border-left:4px solid; + border-color: #FF0000; +} + +dl.pre, dl.post, dl.invariant +{ + margin-left:-7px; + padding-left: 3px; + border-left:4px solid; + border-color: #00D000; +} + +dl.deprecated +{ + margin-left:-7px; + padding-left: 3px; + border-left:4px solid; + border-color: #505050; +} + +dl.todo +{ + margin-left:-7px; + padding-left: 3px; + border-left:4px solid; + border-color: #00C0E0; +} + +dl.test +{ + margin-left:-7px; + padding-left: 3px; + border-left:4px solid; + border-color: #3030E0; +} + +dl.bug +{ + margin-left:-7px; + padding-left: 3px; + border-left:4px solid; + border-color: #C08050; +} + +dl.section dd { + margin-bottom: 6px; +} + + +#projectlogo +{ + text-align: center; + vertical-align: bottom; + border-collapse: separate; +} + +#projectlogo img +{ + border: 0px none; +} + +#projectname +{ + font: 300% Tahoma, Arial,sans-serif; + margin: 0px; + padding: 2px 0px; +} + +#projectbrief +{ + font: 120% Tahoma, Arial,sans-serif; + margin: 0px; + padding: 0px; +} + +#projectnumber +{ + font: 50% Tahoma, Arial,sans-serif; + margin: 0px; + padding: 0px; +} + +#titlearea +{ + padding: 0px; + margin: 0px; + width: 100%; + border-bottom: 1px solid #5373B4; +} + +.image +{ + text-align: center; +} + +.dotgraph +{ + text-align: center; +} + +.mscgraph +{ + text-align: center; +} + +.caption +{ + font-weight: bold; +} + +div.zoom +{ + border: 1px solid #90A5CE; +} + +dl.citelist { + margin-bottom:50px; +} + +dl.citelist dt { + color:#334975; + float:left; + font-weight:bold; + margin-right:10px; + padding:5px; +} + +dl.citelist dd { + margin:2px 0; + padding:5px 0; +} + +div.toc { + padding: 14px 25px; + background-color: #F4F6FA; + border: 1px solid #D8DFEE; + border-radius: 7px 7px 7px 7px; + float: right; + height: auto; + margin: 0 20px 10px 10px; + width: 200px; +} + +div.toc li { + background: url("bdwn.png") no-repeat scroll 0 5px transparent; + font: 10px/1.2 Verdana,DejaVu Sans,Geneva,sans-serif; + margin-top: 5px; + padding-left: 10px; + padding-top: 2px; +} + +div.toc h3 { + font: bold 12px/1.2 Arial,FreeSans,sans-serif; + color: #4665A2; + border-bottom: 0 none; + margin: 0; +} + +div.toc ul { + list-style: none outside none; + border: medium none; + padding: 0px; +} + +div.toc li.level1 { + margin-left: 0px; +} + +div.toc li.level2 { + margin-left: 15px; +} + +div.toc li.level3 { + margin-left: 30px; +} + +div.toc li.level4 { + margin-left: 45px; +} + +.inherit_header { + font-weight: bold; + color: gray; + cursor: pointer; + -webkit-touch-callout: none; + -webkit-user-select: none; + -khtml-user-select: none; + -moz-user-select: none; + -ms-user-select: none; + user-select: none; +} + +.inherit_header td { + padding: 6px 0px 2px 5px; +} + +.inherit { + display: none; +} + +tr.heading h2 { + margin-top: 12px; + margin-bottom: 4px; +} + +@media print +{ + #top { display: none; } + #side-nav { display: none; } + #nav-path { display: none; } + body { overflow:visible; } + h1, h2, h3, h4, h5, h6 { page-break-after: avoid; } + .summary { display: none; } + .memitem { page-break-inside: avoid; } + #doc-content + { + margin-left:0 !important; + height:auto !important; + width:auto !important; + overflow:inherit; + display:inline; + } +} + diff --git a/software/firmware/libraries/modbus/documentation/html/dynsections.js b/software/firmware/libraries/modbus/documentation/html/dynsections.js new file mode 100644 index 0000000..ed092c7 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/html/dynsections.js @@ -0,0 +1,97 @@ +function toggleVisibility(linkObj) +{ + var base = $(linkObj).attr('id'); + var summary = $('#'+base+'-summary'); + var content = $('#'+base+'-content'); + var trigger = $('#'+base+'-trigger'); + var src=$(trigger).attr('src'); + if (content.is(':visible')===true) { + content.hide(); + summary.show(); + $(linkObj).addClass('closed').removeClass('opened'); + $(trigger).attr('src',src.substring(0,src.length-8)+'closed.png'); + } else { + content.show(); + summary.hide(); + $(linkObj).removeClass('closed').addClass('opened'); + $(trigger).attr('src',src.substring(0,src.length-10)+'open.png'); + } + return false; +} + +function updateStripes() +{ + $('table.directory tr'). + removeClass('even').filter(':visible:even').addClass('even'); +} +function toggleLevel(level) +{ + $('table.directory tr').each(function(){ + var l = this.id.split('_').length-1; + var i = $('#img'+this.id.substring(3)); + var a = $('#arr'+this.id.substring(3)); + if (l + + + + + +Modbus Master and Slave for Arduino: File List + + + + + + +
+
+ + + + + + +
+
Modbus Master and Slave for Arduino +  1.2 +
+
Arduino library for implementing a Modbus Master or Slave through Serial port
+
+
+ + + + +
+
+
+
File List
+
+
+
Here is a list of all files with brief descriptions:
+ + +
\*ModbusRtu.h
+
+
+ + + + diff --git a/software/firmware/libraries/modbus/documentation/html/functions.html b/software/firmware/libraries/modbus/documentation/html/functions.html new file mode 100644 index 0000000..50151b1 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/html/functions.html @@ -0,0 +1,126 @@ + + + + + + +Modbus Master and Slave for Arduino: Class Members + + + + + + +
+
+ + + + + + +
+
Modbus Master and Slave for Arduino +  1.2 +
+
Arduino library for implementing a Modbus Master or Slave through Serial port
+
+
+ + + + + +
+
+
Here is a list of all class members with links to the classes they belong to:
+
+ + + + diff --git a/software/firmware/libraries/modbus/documentation/html/functions_func.html b/software/firmware/libraries/modbus/documentation/html/functions_func.html new file mode 100644 index 0000000..2d18bd7 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/html/functions_func.html @@ -0,0 +1,111 @@ + + + + + + +Modbus Master and Slave for Arduino: Class Members - Functions + + + + + + +
+
+ + + + + + +
+
Modbus Master and Slave for Arduino +  1.2 +
+
Arduino library for implementing a Modbus Master or Slave through Serial port
+
+
+ + + + + +
+
+
+ + + + diff --git a/software/firmware/libraries/modbus/documentation/html/functions_vars.html b/software/firmware/libraries/modbus/documentation/html/functions_vars.html new file mode 100644 index 0000000..dcecec1 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/html/functions_vars.html @@ -0,0 +1,81 @@ + + + + + + +Modbus Master and Slave for Arduino: Class Members - Variables + + + + + + +
+
+ + + + + + +
+
Modbus Master and Slave for Arduino +  1.2 +
+
Arduino library for implementing a Modbus Master or Slave through Serial port
+
+
+ + + + + +
+
+
+ + + + diff --git a/software/firmware/libraries/modbus/documentation/html/globals.html b/software/firmware/libraries/modbus/documentation/html/globals.html new file mode 100644 index 0000000..da39994 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/html/globals.html @@ -0,0 +1,233 @@ + + + + + + +Modbus Master and Slave for Arduino: File Members + + + + + + +
+
+ + + + + + +
+
Modbus Master and Slave for Arduino +  1.2 +
+
Arduino library for implementing a Modbus Master or Slave through Serial port
+
+
+ + + + + + +
+
+
Here is a list of all file members with links to the files they belong to:
+ +

- a -

+ + +

- b -

+ + +

- c -

+ + +

- e -

+ + +

- f -

+ + +

- i -

+ + +

- m -

+ + +

- n -

+ + +

- r -

+ + +

- t -

+
+ + + + diff --git a/software/firmware/libraries/modbus/documentation/html/globals_defs.html b/software/firmware/libraries/modbus/documentation/html/globals_defs.html new file mode 100644 index 0000000..3bb4d7f --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/html/globals_defs.html @@ -0,0 +1,73 @@ + + + + + + +Modbus Master and Slave for Arduino: File Members + + + + + + +
+
+ + + + + + +
+
Modbus Master and Slave for Arduino +  1.2 +
+
Arduino library for implementing a Modbus Master or Slave through Serial port
+
+
+ + + + + +
+
+
+ + + + diff --git a/software/firmware/libraries/modbus/documentation/html/globals_enum.html b/software/firmware/libraries/modbus/documentation/html/globals_enum.html new file mode 100644 index 0000000..4b289fe --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/html/globals_enum.html @@ -0,0 +1,79 @@ + + + + + + +Modbus Master and Slave for Arduino: File Members + + + + + + +
+
+ + + + + + +
+
Modbus Master and Slave for Arduino +  1.2 +
+
Arduino library for implementing a Modbus Master or Slave through Serial port
+
+
+ + + + + +
+
+
+ + + + diff --git a/software/firmware/libraries/modbus/documentation/html/globals_eval.html b/software/firmware/libraries/modbus/documentation/html/globals_eval.html new file mode 100644 index 0000000..1d9d736 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/html/globals_eval.html @@ -0,0 +1,207 @@ + + + + + + +Modbus Master and Slave for Arduino: File Members + + + + + + +
+
+ + + + + + +
+
Modbus Master and Slave for Arduino +  1.2 +
+
Arduino library for implementing a Modbus Master or Slave through Serial port
+
+
+ + + + + + +
+
+  + +

- a -

+ + +

- b -

+ + +

- c -

+ + +

- e -

+ + +

- f -

+ + +

- i -

+ + +

- m -

+ + +

- n -

+ + +

- r -

+
+ + + + diff --git a/software/firmware/libraries/modbus/documentation/html/globals_vars.html b/software/firmware/libraries/modbus/documentation/html/globals_vars.html new file mode 100644 index 0000000..8f00b2b --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/html/globals_vars.html @@ -0,0 +1,70 @@ + + + + + + +Modbus Master and Slave for Arduino: File Members + + + + + + +
+
+ + + + + + +
+
Modbus Master and Slave for Arduino +  1.2 +
+
Arduino library for implementing a Modbus Master or Slave through Serial port
+
+
+ + + + + +
+
+
+ + + + diff --git a/software/firmware/libraries/modbus/documentation/html/group__buffer.html b/software/firmware/libraries/modbus/documentation/html/group__buffer.html new file mode 100644 index 0000000..c3e941e --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/html/group__buffer.html @@ -0,0 +1,184 @@ + + + + + + +Modbus Master and Slave for Arduino: Modbus Buffer Management + + + + + + +
+
+ + + + + + +
+
Modbus Master and Slave for Arduino +  1.2 +
+
Arduino library for implementing a Modbus Master or Slave through Serial port
+
+
+ + + +
+
+ +
+
Modbus Buffer Management
+
+
+ + + + + + + + + + + + + + + + +

+Functions

uint16_t Modbus::getInCnt ()
 number of incoming messages More...
 
uint16_t Modbus::getOutCnt ()
 number of outcoming messages More...
 
uint16_t Modbus::getErrCnt ()
 error counter More...
 
uint8_t Modbus::getState ()
 
uint8_t Modbus::getLastError ()
 get last error message More...
 
+

Detailed Description

+

Function Documentation

+ +
+
+ + + + + + + +
uint16_t Modbus::getErrCnt ()
+
+ +

error counter

+

Get errors counter value This can be useful to diagnose communication.

+
Returns
errors counter
+ +

Definition at line 386 of file ModbusRtu.h.

+ +
+
+ +
+
+ + + + + + + +
uint16_t Modbus::getInCnt ()
+
+ +

number of incoming messages

+

Get input messages counter value This can be useful to diagnose communication.

+
Returns
input messages counter
+ +

Definition at line 362 of file ModbusRtu.h.

+ +
+
+ +
+
+ + + + + + + +
uint8_t Modbus::getLastError ()
+
+ +

get last error message

+

Get the last error in the protocol processor

+

NO_REPLY = 255 Time-out

+
Returns
EXC_FUNC_CODE = 1 Function code not available
+
+EXC_ADDR_RANGE = 2 Address beyond available space for Modbus registers
+
+EXC_REGS_QUANT = 3 Coils or registers number beyond the available space
+ +

Definition at line 409 of file ModbusRtu.h.

+ +
+
+ +
+
+ + + + + + + +
uint16_t Modbus::getOutCnt ()
+
+ +

number of outcoming messages

+

Get transmitted messages counter value This can be useful to diagnose communication.

+
Returns
transmitted messages counter
+ +

Definition at line 374 of file ModbusRtu.h.

+ +
+
+ +
+
+ + + + + + + +
uint8_t Modbus::getState ()
+
+

Get modbus master state

+
Returns
= 0 IDLE, = 1 WAITING FOR ANSWER
+ +

Definition at line 396 of file ModbusRtu.h.

+ +
+
+
+ + + + diff --git a/software/firmware/libraries/modbus/documentation/html/group__discrete.html b/software/firmware/libraries/modbus/documentation/html/group__discrete.html new file mode 100644 index 0000000..15de7c2 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/html/group__discrete.html @@ -0,0 +1,55 @@ + + + + + + +Modbus Master and Slave for Arduino: Modbus Function Codes for Discrete Coils/Inputs + + + + + + +
+
+ + + + + + +
+
Modbus Master and Slave for Arduino +  1.2 +
+
Arduino library for implementing a Modbus Master or Slave through Serial port
+
+
+ + + +
+
+
+
Modbus Function Codes for Discrete Coils/Inputs
+
+
+

Detailed Description

+
+ + + + diff --git a/software/firmware/libraries/modbus/documentation/html/group__loop.html b/software/firmware/libraries/modbus/documentation/html/group__loop.html new file mode 100644 index 0000000..f90e3f8 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/html/group__loop.html @@ -0,0 +1,186 @@ + + + + + + +Modbus Master and Slave for Arduino: Modbus Object Management + + + + + + +
+
+ + + + + + +
+
Modbus Master and Slave for Arduino +  1.2 +
+
Arduino library for implementing a Modbus Master or Slave through Serial port
+
+
+ + + +
+
+ +
+
Modbus Object Management
+
+
+ + + + + + + + + + + + + + +

+Functions

boolean Modbus::getTimeOutState ()
 get communication watch-dog timer state More...
 
int8_t Modbus::query (modbus_t telegram)
 only for master More...
 
int8_t Modbus::poll ()
 cyclic poll for master More...
 
int8_t Modbus::poll (uint16_t *regs, uint8_t u8size)
 cyclic poll for slave More...
 
+

Detailed Description

+

Function Documentation

+ +
+
+ + + + + + + +
boolean Modbus::getTimeOutState ()
+
+ +

get communication watch-dog timer state

+

Return communication Watchdog state. It could be usefull to reset outputs if the watchdog is fired.

+
Returns
TRUE if millis() > u32timeOut
+ +

Definition at line 350 of file ModbusRtu.h.

+ +
+
+ +
+
+ + + + + + + +
int8_t Modbus::poll ()
+
+ +

cyclic poll for master

+

*** Only for Modbus Master *** This method checks if there is any incoming answer if pending. If there is no answer, it would change Master state to COM_IDLE. This method must be called only at loop section. Avoid any delay() function.

+

Any incoming data would be redirected to au16regs pointer, as defined in its modbus_t query telegram.

+

nothing

+
Returns
errors counter
+ +

Definition at line 513 of file ModbusRtu.h.

+ +
+
+ +
+
+ + + + + + + + + + + + + + + + + + +
int8_t Modbus::poll (uint16_t * regs,
uint8_t u8size 
)
+
+ +

cyclic poll for slave

+

*** Only for Modbus Slave *** This method checks if there is any incoming query Afterwards, it would shoot a validation routine plus a register query Avoid any delay() function !!!! After a successful frame between the Master and the Slave, the time-out timer is reset.

+
Parameters
+ + + +
*regsregister table for communication exchange
u8sizesize of the register table
+
+
+
Returns
0 if no query, 1..4 if communication error, >4 if correct query processed
+ +

Definition at line 588 of file ModbusRtu.h.

+ +
+
+ +
+
+ + + + + + + + +
int8_t Modbus::query (modbus_t telegram)
+
+ +

only for master

+

*** Only Modbus Master *** Generate a query to an slave with a modbus_t telegram structure The Master must be in COM_IDLE mode. After it, its state would be COM_WAITING. This method has to be called only in loop() section.

+
See Also
modbus_t
+
Parameters
+ + +
modbus_tmodbus telegram structure (id, fct, ...)
+
+
+
Todo:
finish function 15
+ +

Definition at line 425 of file ModbusRtu.h.

+ +
+
+
+ + + + diff --git a/software/firmware/libraries/modbus/documentation/html/group__register.html b/software/firmware/libraries/modbus/documentation/html/group__register.html new file mode 100644 index 0000000..eb40488 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/html/group__register.html @@ -0,0 +1,55 @@ + + + + + + +Modbus Master and Slave for Arduino: Modbus Function Codes for Holding/Input Registers + + + + + + +
+
+ + + + + + +
+
Modbus Master and Slave for Arduino +  1.2 +
+
Arduino library for implementing a Modbus Master or Slave through Serial port
+
+
+ + + +
+
+
+
Modbus Function Codes for Holding/Input Registers
+
+
+

Detailed Description

+
+ + + + diff --git a/software/firmware/libraries/modbus/documentation/html/group__setup.html b/software/firmware/libraries/modbus/documentation/html/group__setup.html new file mode 100644 index 0000000..295df48 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/html/group__setup.html @@ -0,0 +1,201 @@ + + + + + + +Modbus Master and Slave for Arduino: Modbus Object Instantiation/Initialization + + + + + + +
+
+ + + + + + +
+
Modbus Master and Slave for Arduino +  1.2 +
+
Arduino library for implementing a Modbus Master or Slave through Serial port
+
+
+ + + +
+
+ +
+
Modbus Object Instantiation/Initialization
+
+
+ + + + + + + + + + + + + + + + + +

+Functions

 Modbus::Modbus ()
 Default Constructor for Master through Serial. More...
 
void Modbus::begin (long u32speed)
 Initialize class object. More...
 
void Modbus::setID (uint8_t u8id)
 write new ID for the slave More...
 
uint8_t Modbus::getID ()
 get slave ID between 1 and 247 More...
 
void Modbus::setTimeOut (uint16_t u16timeout)
 write communication watch-dog timer More...
 
+

Detailed Description

+

Function Documentation

+ +
+
+ + + + + + + + +
void Modbus::begin (long u32speed)
+
+ +

Initialize class object.

+

Sets up the serial port using specified baud rate. Call once class has been instantiated, typically within setup().

+
See Also
http://arduino.cc/en/Serial/Begin#.Uy4CJ6aKlHY
+
Parameters
+ + + +
speedbaud rate, in standard increments (300..115200)
configdata frame settings (data length, parity and stop bits)
+
+
+ +

Definition at line 250 of file ModbusRtu.h.

+ +
+
+ +
+
+ + + + + + + +
uint8_t Modbus::getID ()
+
+ +

get slave ID between 1 and 247

+

Method to read current slave ID address.

+
Returns
u8id current slave address between 1 and 247
+ +

Definition at line 323 of file ModbusRtu.h.

+ +
+
+ +
+
+ + + + + + + +
Modbus::Modbus ()
+
+ +

Default Constructor for Master through Serial.

+ +

Definition at line 204 of file ModbusRtu.h.

+ +
+
+ +
+
+ + + + + + + + +
void Modbus::setID (uint8_t u8id)
+
+ +

write new ID for the slave

+

Method to write a new slave ID address.

+
Parameters
+ + +
u8idnew slave address between 1 and 247
+
+
+ +

Definition at line 310 of file ModbusRtu.h.

+ +
+
+ +
+
+ + + + + + + + +
void Modbus::setTimeOut (uint16_t u16timeOut)
+
+ +

write communication watch-dog timer

+

Initialize time-out parameter.

+

Call once class has been instantiated, typically within setup(). The time-out timer is reset each time that there is a successful communication between Master and Slave. It works for both.

+
Parameters
+ + +
time-outvalue (ms)
+
+
+ +

Definition at line 338 of file ModbusRtu.h.

+ +
+
+
+ + + + diff --git a/software/firmware/libraries/modbus/documentation/html/index.hhc b/software/firmware/libraries/modbus/documentation/html/index.hhc new file mode 100644 index 0000000..5d4eef8 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/html/index.hhc @@ -0,0 +1,178 @@ + + + + + +
    +
  • +
  • +
      +
    • +
        +
      • +
      • +
      • +
      • +
      • +
      +
    • +
        +
      • +
      • +
      • +
      • +
      +
    • +
        +
      • +
      • +
      • +
      • +
      • +
      +
    • +
        +
      +
    • +
        +
      +
    +
  • +
      +
    • +
        +
      • +
          +
        • +
        • +
        • +
        • +
        • +
        • +
        • +
        • +
        • +
        • +
        • +
        • +
        • +
        • +
        • +
        • +
        • +
        • +
        • +
        +
      • +
          +
        • +
        • +
        • +
        • +
        • +
        +
      +
    • +
    • +
        +
      • +
      • +
      • +
      +
    +
  • +
      +
    • +
        +
      • +
          +
        • +
            +
          • +
          • +
          • +
          • +
          • +
          +
        • +
            +
          • +
          • +
          • +
          • +
          • +
          • +
          • +
          • +
          • +
          • +
          • +
          • +
          • +
          • +
          • +
          • +
          • +
          • +
          • +
          +
        • +
        • +
        • +
        • +
        • +
        • +
        • +
        • +
        • +
        • +
        • +
            +
          • +
          • +
          +
        • +
            +
          • +
          • +
          • +
          • +
          • +
          +
        • +
            +
          • +
          • +
          • +
          • +
          • +
          • +
          • +
          • +
          • +
          +
        • +
            +
          • +
          • +
          • +
          • +
          • +
          • +
          • +
          +
        • +
        +
      +
    • +
        +
      • +
      • +
      • +
      • +
      • +
      +
    +
+ + diff --git a/software/firmware/libraries/modbus/documentation/html/index.hhk b/software/firmware/libraries/modbus/documentation/html/index.hhk new file mode 100644 index 0000000..9a9a2df --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/html/index.hhk @@ -0,0 +1,203 @@ + + + + + +
    +
  • +
  • +
  • +
  • +
      +
    • +
    • +
    +
  • +
      +
    • +
    • +
    • +
    • +
    • +
    +
  • +
  • +
  • +
  • +
  • +
  • +
  • +
  • +
  • +
  • +
  • +
  • +
  • +
  • +
  • +
  • +
  • +
  • +
      +
    • +
    • +
    +
  • +
      +
    • +
    • +
    +
  • +
      +
    • +
    • +
    +
  • +
      +
    • +
    • +
    +
  • +
      +
    • +
    • +
    +
  • +
      +
    • +
    • +
    +
  • +
  • +
      +
    • +
    • +
    +
  • +
  • +
      +
    • +
    • +
    • +
    +
  • +
  • +
  • +
  • +
  • +
  • +
  • +
  • +
  • +
  • +
  • +
  • +
  • +
  • +
  • +
  • +
  • +
      +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    +
  • +
      +
    • +
    • +
    • +
    • +
    • +
    +
  • +
      +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    • +
    +
  • +
  • +
  • +
  • +
      +
    • +
    • +
    +
  • +
      +
    • +
    • +
    +
  • +
  • +
      +
    • +
    • +
    +
  • +
      +
    • +
    • +
    +
  • +
      +
    • +
    • +
    • +
    • +
    • +
    +
  • +
  • +
  • +
  • +
  • +
  • +
+ + diff --git a/software/firmware/libraries/modbus/documentation/html/index.hhp b/software/firmware/libraries/modbus/documentation/html/index.hhp new file mode 100644 index 0000000..789dbbd --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/html/index.hhp @@ -0,0 +1,69 @@ +[OPTIONS] +Compatibility=1.1 +Full-text search=Yes +Contents file=index.hhc +Default Window=main +Default topic=index.html +Index file=index.hhk +Language=0x409 English (United States) +Title=Modbus Master and Slave for Arduino + +[WINDOWS] +main="Modbus Master and Slave for Arduino","index.hhc","index.hhk","index.html","index.html",,,,,0x23520,,0x10387e,,,,,,,,0 + +[FILES] +_modbus_rtu_8h_source.html +_modbus_rtu_8h.html +todo.html +group__setup.html +group__loop.html +group__buffer.html +group__discrete.html +group__register.html +class_modbus.html +class_modbus-members.html +structmodbus__t.html +structmodbus__t-members.html +index.html +pages.html +modules.html +annotated.html +classes.html +functions.html +functions_func.html +functions_vars.html +files.html +globals.html +globals_vars.html +globals_enum.html +globals_eval.html +globals_defs.html +tab_a.png +tab_b.png +tab_h.png +tab_s.png +nav_h.png +nav_f.png +bc_s.png +doxygen.png +closed.png +open.png +bdwn.png +sync_on.png +sync_off.png +ftv2blank.png +ftv2doc.png +ftv2folderclosed.png +ftv2folderopen.png +ftv2ns.png +ftv2mo.png +ftv2cl.png +ftv2lastnode.png +ftv2link.png +ftv2mlastnode.png +ftv2mnode.png +ftv2node.png +ftv2plastnode.png +ftv2pnode.png +ftv2vertline.png +ftv2splitbar.png diff --git a/software/firmware/libraries/modbus/documentation/html/index.html b/software/firmware/libraries/modbus/documentation/html/index.html new file mode 100644 index 0000000..551c1ef --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/html/index.html @@ -0,0 +1,54 @@ + + + + + + +Modbus Master and Slave for Arduino: Main Page + + + + + + +
+
+ + + + + + +
+
Modbus Master and Slave for Arduino +  1.2 +
+
Arduino library for implementing a Modbus Master or Slave through Serial port
+
+
+ + + +
+
+
+
Modbus Master and Slave for Arduino Documentation
+
+
+
+ + + + diff --git a/software/firmware/libraries/modbus/documentation/html/modules.html b/software/firmware/libraries/modbus/documentation/html/modules.html new file mode 100644 index 0000000..f78fcc9 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/html/modules.html @@ -0,0 +1,63 @@ + + + + + + +Modbus Master and Slave for Arduino: Modules + + + + + + +
+
+ + + + + + +
+
Modbus Master and Slave for Arduino +  1.2 +
+
Arduino library for implementing a Modbus Master or Slave through Serial port
+
+
+ + + +
+
+
+
Modules
+
+ + + + + diff --git a/software/firmware/libraries/modbus/documentation/html/pages.html b/software/firmware/libraries/modbus/documentation/html/pages.html new file mode 100644 index 0000000..a24422d --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/html/pages.html @@ -0,0 +1,59 @@ + + + + + + +Modbus Master and Slave for Arduino: Related Pages + + + + + + +
+
+ + + + + + +
+
Modbus Master and Slave for Arduino +  1.2 +
+
Arduino library for implementing a Modbus Master or Slave through Serial port
+
+
+ + + +
+
+
+
Related Pages
+
+
+
Here is a list of all related documentation pages:
+ + +
\Todo List
+
+
+ + + + diff --git a/software/firmware/libraries/modbus/documentation/html/structmodbus__t-members.html b/software/firmware/libraries/modbus/documentation/html/structmodbus__t-members.html new file mode 100644 index 0000000..a3cd981 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/html/structmodbus__t-members.html @@ -0,0 +1,69 @@ + + + + + + +Modbus Master and Slave for Arduino: Member List + + + + + + +
+
+ + + + + + +
+
Modbus Master and Slave for Arduino +  1.2 +
+
Arduino library for implementing a Modbus Master or Slave through Serial port
+
+
+ + + + +
+
+
+
modbus_t Member List
+
+
+ +

This is the complete list of members for modbus_t, including all inherited members.

+ + + + + + +
au16regmodbus_t
u16CoilsNomodbus_t
u16RegAddmodbus_t
u8fctmodbus_t
u8idmodbus_t
+ + + + diff --git a/software/firmware/libraries/modbus/documentation/html/structmodbus__t.html b/software/firmware/libraries/modbus/documentation/html/structmodbus__t.html new file mode 100644 index 0000000..5b55617 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/html/structmodbus__t.html @@ -0,0 +1,166 @@ + + + + + + +Modbus Master and Slave for Arduino: modbus_t Struct Reference + + + + + + +
+
+ + + + + + +
+
Modbus Master and Slave for Arduino +  1.2 +
+
Arduino library for implementing a Modbus Master or Slave through Serial port
+
+
+ + + + +
+
+ +
+
modbus_t Struct Reference
+
+
+ +

Master query structure: This includes all the necessary fields to make the Master generate a Modbus query. A Master may keep several of these structures and send them cyclically or use them according to program needs. + More...

+ +

#include <ModbusRtu.h>

+ + + + + + + + + + + + +

+Public Attributes

uint8_t u8id
 
uint8_t u8fct
 
uint16_t u16RegAdd
 
uint16_t u16CoilsNo
 
uint16_t * au16reg
 
+

Detailed Description

+

Master query structure: This includes all the necessary fields to make the Master generate a Modbus query. A Master may keep several of these structures and send them cyclically or use them according to program needs.

+ +

Definition at line 48 of file ModbusRtu.h.

+

Member Data Documentation

+ +
+
+ + + + +
uint16_t* modbus_t::au16reg
+
+

Pointer to memory image in master

+ +

Definition at line 53 of file ModbusRtu.h.

+ +
+
+ +
+
+ + + + +
uint16_t modbus_t::u16CoilsNo
+
+

Number of coils or registers to access

+ +

Definition at line 52 of file ModbusRtu.h.

+ +
+
+ +
+
+ + + + +
uint16_t modbus_t::u16RegAdd
+
+

Address of the first register to access at slave/s

+ +

Definition at line 51 of file ModbusRtu.h.

+ +
+
+ +
+
+ + + + +
uint8_t modbus_t::u8fct
+
+

Function code: 1, 2, 3, 4, 5, 6, 15 or 16

+ +

Definition at line 50 of file ModbusRtu.h.

+ +
+
+ +
+
+ + + + +
uint8_t modbus_t::u8id
+
+

Slave address between 1 and 247. 0 means broadcast

+ +

Definition at line 49 of file ModbusRtu.h.

+ +
+
+
The documentation for this struct was generated from the following file: +
+ + + + diff --git a/software/firmware/libraries/modbus/documentation/html/tabs.css b/software/firmware/libraries/modbus/documentation/html/tabs.css new file mode 100644 index 0000000..9cf578f --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/html/tabs.css @@ -0,0 +1,60 @@ +.tabs, .tabs2, .tabs3 { + background-image: url('tab_b.png'); + width: 100%; + z-index: 101; + font-size: 13px; + font-family: 'Lucida Grande',Geneva,Helvetica,Arial,sans-serif; +} + +.tabs2 { + font-size: 10px; +} +.tabs3 { + font-size: 9px; +} + +.tablist { + margin: 0; + padding: 0; + display: table; +} + +.tablist li { + float: left; + display: table-cell; + background-image: url('tab_b.png'); + line-height: 36px; + list-style: none; +} + +.tablist a { + display: block; + padding: 0 20px; + font-weight: bold; + background-image:url('tab_s.png'); + background-repeat:no-repeat; + background-position:right; + color: #283A5D; + text-shadow: 0px 1px 1px rgba(255, 255, 255, 0.9); + text-decoration: none; + outline: none; +} + +.tabs3 .tablist a { + padding: 0 10px; +} + +.tablist a:hover { + background-image: url('tab_h.png'); + background-repeat:repeat-x; + color: #fff; + text-shadow: 0px 1px 1px rgba(0, 0, 0, 1.0); + text-decoration: none; +} + +.tablist li.current a { + background-image: url('tab_a.png'); + background-repeat:repeat-x; + color: #fff; + text-shadow: 0px 1px 1px rgba(0, 0, 0, 1.0); +} diff --git a/software/firmware/libraries/modbus/documentation/html/todo.html b/software/firmware/libraries/modbus/documentation/html/todo.html new file mode 100644 index 0000000..9721b93 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/html/todo.html @@ -0,0 +1,58 @@ + + + + + + +Modbus Master and Slave for Arduino: Todo List + + + + + + +
+
+ + + + + + +
+
Modbus Master and Slave for Arduino +  1.2 +
+
Arduino library for implementing a Modbus Master or Slave through Serial port
+
+
+ + + +
+
+
+
Todo List
+
+
+
+
Member Modbus::query (modbus_t telegram)
+
finish function 15
+
+
+ + + + diff --git a/software/firmware/libraries/modbus/documentation/latex/Makefile b/software/firmware/libraries/modbus/documentation/latex/Makefile new file mode 100644 index 0000000..3cc085f --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/latex/Makefile @@ -0,0 +1,21 @@ +all: refman.pdf + +pdf: refman.pdf + +refman.pdf: clean refman.tex + pdflatex refman + makeindex refman.idx + pdflatex refman + latex_count=5 ; \ + while egrep -s 'Rerun (LaTeX|to get cross-references right)' refman.log && [ $$latex_count -gt 0 ] ;\ + do \ + echo "Rerunning latex...." ;\ + pdflatex refman ;\ + latex_count=`expr $$latex_count - 1` ;\ + done + makeindex refman.idx + pdflatex refman + + +clean: + rm -f *.ps *.dvi *.aux *.toc *.idx *.ind *.ilg *.log *.out *.brf *.blg *.bbl refman.pdf diff --git a/software/firmware/libraries/modbus/documentation/latex/_modbus_rtu_8h.tex b/software/firmware/libraries/modbus/documentation/latex/_modbus_rtu_8h.tex new file mode 100644 index 0000000..6e481a5 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/latex/_modbus_rtu_8h.tex @@ -0,0 +1,291 @@ +\hypertarget{_modbus_rtu_8h}{\section{Modbus\-Rtu.\-h File Reference} +\label{_modbus_rtu_8h}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}} +} +\subsection*{Classes} +\begin{DoxyCompactItemize} +\item +struct \hyperlink{structmodbus__t}{modbus\-\_\-t} +\begin{DoxyCompactList}\small\item\em Master query structure\-: This includes all the necessary fields to make the Master generate a \hyperlink{class_modbus}{Modbus} query. A Master may keep several of these structures and send them cyclically or use them according to program needs. \end{DoxyCompactList}\item +class \hyperlink{class_modbus}{Modbus} +\begin{DoxyCompactList}\small\item\em Arduino class library for communicating with \hyperlink{class_modbus}{Modbus} devices over U\-S\-B/\-R\-S232/485 (via R\-T\-U protocol). \end{DoxyCompactList}\end{DoxyCompactItemize} +\subsection*{Macros} +\begin{DoxyCompactItemize} +\item +\#define \hyperlink{_modbus_rtu_8h_ac5a7c6ee8dea0ccb09dfc611bd08a0ac}{T35}~5 +\item +\#define \hyperlink{_modbus_rtu_8h_a1d5dab30b404fab91608086105afc78c}{M\-A\-X\-\_\-\-B\-U\-F\-F\-E\-R}~64 +\begin{DoxyCompactList}\small\item\em maximum size for the communication buffer in bytes \end{DoxyCompactList}\end{DoxyCompactItemize} +\subsection*{Enumerations} +\begin{DoxyCompactItemize} +\item +enum \{ \hyperlink{_modbus_rtu_8h_a06fc87d81c62e9abb8790b6e5713c55bad1acb34c5312efc75c4a007eae09433b}{R\-E\-S\-P\-O\-N\-S\-E\-\_\-\-S\-I\-Z\-E} = 6, +\hyperlink{_modbus_rtu_8h_a06fc87d81c62e9abb8790b6e5713c55ba4bf89c487b3f7e29d56eb3fe657d6c05}{E\-X\-C\-E\-P\-T\-I\-O\-N\-\_\-\-S\-I\-Z\-E} = 3, +\hyperlink{_modbus_rtu_8h_a06fc87d81c62e9abb8790b6e5713c55baefcc8f6d8d181aaef9d131a357b1a332}{C\-H\-E\-C\-K\-S\-U\-M\-\_\-\-S\-I\-Z\-E} = 2 + \} +\item +enum \hyperlink{_modbus_rtu_8h_aa9996e8b4648c78acf6cde2401e230ba}{M\-E\-S\-S\-A\-G\-E} \{ \\* +\hyperlink{_modbus_rtu_8h_aa9996e8b4648c78acf6cde2401e230baa001479a58fb44c39a29b20d565081a68}{I\-D} = 0, +\hyperlink{_modbus_rtu_8h_aa9996e8b4648c78acf6cde2401e230baa389e03ce61ac2d93fd54069187ab58af}{F\-U\-N\-C}, +\hyperlink{_modbus_rtu_8h_aa9996e8b4648c78acf6cde2401e230baad19e7653c9276b91fb590af017de192c}{A\-D\-D\-\_\-\-H\-I}, +\hyperlink{_modbus_rtu_8h_aa9996e8b4648c78acf6cde2401e230baa2cbdff2e20e58233096845bf42acc97c}{A\-D\-D\-\_\-\-L\-O}, +\\* +\hyperlink{_modbus_rtu_8h_aa9996e8b4648c78acf6cde2401e230baa61f961bb4614db2fc51125331f79a9d6}{N\-B\-\_\-\-H\-I}, +\hyperlink{_modbus_rtu_8h_aa9996e8b4648c78acf6cde2401e230baa22b2a3a58501a5bbe69ef569aa7fb30f}{N\-B\-\_\-\-L\-O}, +\hyperlink{_modbus_rtu_8h_aa9996e8b4648c78acf6cde2401e230baaf84036e1dd68a2e160c3394fc083e892}{B\-Y\-T\-E\-\_\-\-C\-N\-T} + \} +\begin{DoxyCompactList}\small\item\em Indexes to telegram frame positions. \end{DoxyCompactList}\item +enum \hyperlink{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6}{M\-B\-\_\-\-F\-C} \{ \\* +\hyperlink{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6a513dc96919a5d5c75f129c1b5b2afea9}{M\-B\-\_\-\-F\-C\-\_\-\-N\-O\-N\-E} = 0, +\hyperlink{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6a0b2250567e3e0e43522a64cdce637ce0}{M\-B\-\_\-\-F\-C\-\_\-\-R\-E\-A\-D\-\_\-\-C\-O\-I\-L\-S} = 1, +\hyperlink{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6ac2b52680d6c0bbe3d3e0e9ec7a88fc2e}{M\-B\-\_\-\-F\-C\-\_\-\-R\-E\-A\-D\-\_\-\-D\-I\-S\-C\-R\-E\-T\-E\-\_\-\-I\-N\-P\-U\-T} = 2, +\hyperlink{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6a0c6066cf0a67a1bb349da35ef31e4e8f}{M\-B\-\_\-\-F\-C\-\_\-\-R\-E\-A\-D\-\_\-\-R\-E\-G\-I\-S\-T\-E\-R\-S} = 3, +\\* +\hyperlink{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6a9b2d4a3fb96e4af559d5330ad0c01c07}{M\-B\-\_\-\-F\-C\-\_\-\-R\-E\-A\-D\-\_\-\-I\-N\-P\-U\-T\-\_\-\-R\-E\-G\-I\-S\-T\-E\-R} = 4, +\hyperlink{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6a90126d6c25fb5711c103e819ccda01c7}{M\-B\-\_\-\-F\-C\-\_\-\-W\-R\-I\-T\-E\-\_\-\-C\-O\-I\-L} = 5, +\hyperlink{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6a74e1ffd48177f0e7e33c2c968a1bd86f}{M\-B\-\_\-\-F\-C\-\_\-\-W\-R\-I\-T\-E\-\_\-\-R\-E\-G\-I\-S\-T\-E\-R} = 6, +\hyperlink{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6ac69c42d25cbc0ef303de57bd3d0e2304}{M\-B\-\_\-\-F\-C\-\_\-\-W\-R\-I\-T\-E\-\_\-\-M\-U\-L\-T\-I\-P\-L\-E\-\_\-\-C\-O\-I\-L\-S} = 15, +\\* +\hyperlink{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6a2ccdcde4f07865ffb47fbea0a01026bb}{M\-B\-\_\-\-F\-C\-\_\-\-W\-R\-I\-T\-E\-\_\-\-M\-U\-L\-T\-I\-P\-L\-E\-\_\-\-R\-E\-G\-I\-S\-T\-E\-R\-S} = 16 + \} +\begin{DoxyCompactList}\small\item\em \hyperlink{class_modbus}{Modbus} function codes summary. These are the implement function codes either for Master or for Slave. \end{DoxyCompactList}\item +enum \hyperlink{_modbus_rtu_8h_a4f165b5bd333856a84635b2594013982}{C\-O\-M\-\_\-\-S\-T\-A\-T\-E\-S} \{ \hyperlink{_modbus_rtu_8h_a4f165b5bd333856a84635b2594013982a3e262bfb13968e43ab8ea55a03ba8b20}{C\-O\-M\-\_\-\-I\-D\-L\-E} = 0, +\hyperlink{_modbus_rtu_8h_a4f165b5bd333856a84635b2594013982ad70b4cc84cc2f21d8b46f73f186dae6b}{C\-O\-M\-\_\-\-W\-A\-I\-T\-I\-N\-G} = 1 + \} +\item +enum \hyperlink{_modbus_rtu_8h_a792f00821300f1c7c768db990db646c1}{E\-R\-R\-\_\-\-L\-I\-S\-T} \{ \\* +\hyperlink{_modbus_rtu_8h_a792f00821300f1c7c768db990db646c1a12a9ad0aaae512b253a9da9ea19f2b04}{E\-R\-R\-\_\-\-N\-O\-T\-\_\-\-M\-A\-S\-T\-E\-R} = -\/1, +\hyperlink{_modbus_rtu_8h_a792f00821300f1c7c768db990db646c1a7d2c6c1b333f4b566c613e52b62ab901}{E\-R\-R\-\_\-\-P\-O\-L\-L\-I\-N\-G} = -\/2, +\hyperlink{_modbus_rtu_8h_a792f00821300f1c7c768db990db646c1aafd42890a0ce129e23977fc1aca4044b}{E\-R\-R\-\_\-\-B\-U\-F\-F\-\_\-\-O\-V\-E\-R\-F\-L\-O\-W} = -\/3, +\hyperlink{_modbus_rtu_8h_a792f00821300f1c7c768db990db646c1a918477ee2e5e31f01b03a83f472b63b0}{E\-R\-R\-\_\-\-B\-A\-D\-\_\-\-C\-R\-C} = -\/4, +\\* +\hyperlink{_modbus_rtu_8h_a792f00821300f1c7c768db990db646c1ab4be9b5f7e8905633a3c045157f1dd0a}{E\-R\-R\-\_\-\-E\-X\-C\-E\-P\-T\-I\-O\-N} = -\/5 + \} +\item +enum \{ \\* +\hyperlink{_modbus_rtu_8h_adf764cbdea00d65edcd07bb9953ad2b7aa04c58a8cc2e7777f6f781e8d51524ae}{N\-O\-\_\-\-R\-E\-P\-L\-Y} = 255, +\hyperlink{_modbus_rtu_8h_adf764cbdea00d65edcd07bb9953ad2b7ad82ec66545269170f1401af6e418e8f2}{E\-X\-C\-\_\-\-F\-U\-N\-C\-\_\-\-C\-O\-D\-E} = 1, +\hyperlink{_modbus_rtu_8h_adf764cbdea00d65edcd07bb9953ad2b7ad3899b13b2069997f5db7f18e9978280}{E\-X\-C\-\_\-\-A\-D\-D\-R\-\_\-\-R\-A\-N\-G\-E} = 2, +\hyperlink{_modbus_rtu_8h_adf764cbdea00d65edcd07bb9953ad2b7a062e13fdfefabb1d620506a526be3920}{E\-X\-C\-\_\-\-R\-E\-G\-S\-\_\-\-Q\-U\-A\-N\-T} = 3, +\\* +\hyperlink{_modbus_rtu_8h_adf764cbdea00d65edcd07bb9953ad2b7a00e93edc9146c12fd21490d1a0d15f89}{E\-X\-C\-\_\-\-E\-X\-E\-C\-U\-T\-E} = 4 + \} +\end{DoxyCompactItemize} +\subsection*{Variables} +\begin{DoxyCompactItemize} +\item +const unsigned char \hyperlink{_modbus_rtu_8h_aede21762dc4aa80a14df8dd40ef105f0}{fctsupported} \mbox{[}$\,$\mbox{]} +\end{DoxyCompactItemize} + + +\subsection{Detailed Description} +\begin{DoxyVersion}{Version} +1.\-2 +\end{DoxyVersion} +\begin{DoxyDate}{Date} +2014.\-09.\-09 +\end{DoxyDate} +\begin{DoxyAuthor}{Author} +Samuel Marco i Armengol \href{mailto:sammarcoarmengol@gmail.com}{\tt sammarcoarmengol@gmail.\-com} +\end{DoxyAuthor} +Arduino library for communicating with \hyperlink{class_modbus}{Modbus} devices over R\-S232/\-U\-S\-B/485 via R\-T\-U protocol. + +Further information\-: \href{http://modbus.org/}{\tt http\-://modbus.\-org/} \href{http://modbus.org/docs/Modbus_over_serial_line_V1_02.pdf}{\tt http\-://modbus.\-org/docs/\-Modbus\-\_\-over\-\_\-serial\-\_\-line\-\_\-\-V1\-\_\-02.\-pdf} + +This library is free software; you can redistribute it and/or modify it under the terms of the G\-N\-U Lesser General Public License as published by the Free Software Foundation; version 2.\-1 of the License. + +This library is distributed in the hope that it will be useful, but W\-I\-T\-H\-O\-U\-T A\-N\-Y W\-A\-R\-R\-A\-N\-T\-Y; without even the implied warranty of M\-E\-R\-C\-H\-A\-N\-T\-A\-B\-I\-L\-I\-T\-Y or F\-I\-T\-N\-E\-S\-S F\-O\-R A P\-A\-R\-T\-I\-C\-U\-L\-A\-R P\-U\-R\-P\-O\-S\-E. See the G\-N\-U Lesser General Public License for more details. + +You should have received a copy of the G\-N\-U Lesser General Public License along with this library; if not, write to the Free Software Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, M\-A 02110-\/1301 U\-S\-A + +Definition in file \hyperlink{_modbus_rtu_8h_source}{Modbus\-Rtu.\-h}. + + + +\subsection{Macro Definition Documentation} +\hypertarget{_modbus_rtu_8h_a1d5dab30b404fab91608086105afc78c}{\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!M\-A\-X\-\_\-\-B\-U\-F\-F\-E\-R@{M\-A\-X\-\_\-\-B\-U\-F\-F\-E\-R}} +\index{M\-A\-X\-\_\-\-B\-U\-F\-F\-E\-R@{M\-A\-X\-\_\-\-B\-U\-F\-F\-E\-R}!ModbusRtu.h@{Modbus\-Rtu.\-h}} +\subsubsection[{M\-A\-X\-\_\-\-B\-U\-F\-F\-E\-R}]{\setlength{\rightskip}{0pt plus 5cm}\#define M\-A\-X\-\_\-\-B\-U\-F\-F\-E\-R~64}}\label{_modbus_rtu_8h_a1d5dab30b404fab91608086105afc78c} + + +maximum size for the communication buffer in bytes + + + +Definition at line 133 of file Modbus\-Rtu.\-h. + +\hypertarget{_modbus_rtu_8h_ac5a7c6ee8dea0ccb09dfc611bd08a0ac}{\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!T35@{T35}} +\index{T35@{T35}!ModbusRtu.h@{Modbus\-Rtu.\-h}} +\subsubsection[{T35}]{\setlength{\rightskip}{0pt plus 5cm}\#define T35~5}}\label{_modbus_rtu_8h_ac5a7c6ee8dea0ccb09dfc611bd08a0ac} + + +Definition at line 132 of file Modbus\-Rtu.\-h. + + + +\subsection{Enumeration Type Documentation} +\hypertarget{_modbus_rtu_8h_a06fc87d81c62e9abb8790b6e5713c55b}{\subsubsection[{anonymous enum}]{\setlength{\rightskip}{0pt plus 5cm}anonymous enum}}\label{_modbus_rtu_8h_a06fc87d81c62e9abb8790b6e5713c55b} +\begin{Desc} +\item[Enumerator]\par +\begin{description} +\index{R\-E\-S\-P\-O\-N\-S\-E\-\_\-\-S\-I\-Z\-E@{R\-E\-S\-P\-O\-N\-S\-E\-\_\-\-S\-I\-Z\-E}!Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!R\-E\-S\-P\-O\-N\-S\-E\-\_\-\-S\-I\-Z\-E@{R\-E\-S\-P\-O\-N\-S\-E\-\_\-\-S\-I\-Z\-E}}\item[{\em +\hypertarget{_modbus_rtu_8h_a06fc87d81c62e9abb8790b6e5713c55bad1acb34c5312efc75c4a007eae09433b}{R\-E\-S\-P\-O\-N\-S\-E\-\_\-\-S\-I\-Z\-E}\label{_modbus_rtu_8h_a06fc87d81c62e9abb8790b6e5713c55bad1acb34c5312efc75c4a007eae09433b} +}]\index{E\-X\-C\-E\-P\-T\-I\-O\-N\-\_\-\-S\-I\-Z\-E@{E\-X\-C\-E\-P\-T\-I\-O\-N\-\_\-\-S\-I\-Z\-E}!Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!E\-X\-C\-E\-P\-T\-I\-O\-N\-\_\-\-S\-I\-Z\-E@{E\-X\-C\-E\-P\-T\-I\-O\-N\-\_\-\-S\-I\-Z\-E}}\item[{\em +\hypertarget{_modbus_rtu_8h_a06fc87d81c62e9abb8790b6e5713c55ba4bf89c487b3f7e29d56eb3fe657d6c05}{E\-X\-C\-E\-P\-T\-I\-O\-N\-\_\-\-S\-I\-Z\-E}\label{_modbus_rtu_8h_a06fc87d81c62e9abb8790b6e5713c55ba4bf89c487b3f7e29d56eb3fe657d6c05} +}]\index{C\-H\-E\-C\-K\-S\-U\-M\-\_\-\-S\-I\-Z\-E@{C\-H\-E\-C\-K\-S\-U\-M\-\_\-\-S\-I\-Z\-E}!Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!C\-H\-E\-C\-K\-S\-U\-M\-\_\-\-S\-I\-Z\-E@{C\-H\-E\-C\-K\-S\-U\-M\-\_\-\-S\-I\-Z\-E}}\item[{\em +\hypertarget{_modbus_rtu_8h_a06fc87d81c62e9abb8790b6e5713c55baefcc8f6d8d181aaef9d131a357b1a332}{C\-H\-E\-C\-K\-S\-U\-M\-\_\-\-S\-I\-Z\-E}\label{_modbus_rtu_8h_a06fc87d81c62e9abb8790b6e5713c55baefcc8f6d8d181aaef9d131a357b1a332} +}]\end{description} +\end{Desc} + + +Definition at line 57 of file Modbus\-Rtu.\-h. + +\hypertarget{_modbus_rtu_8h_adf764cbdea00d65edcd07bb9953ad2b7}{\subsubsection[{anonymous enum}]{\setlength{\rightskip}{0pt plus 5cm}anonymous enum}}\label{_modbus_rtu_8h_adf764cbdea00d65edcd07bb9953ad2b7} +\begin{Desc} +\item[Enumerator]\par +\begin{description} +\index{N\-O\-\_\-\-R\-E\-P\-L\-Y@{N\-O\-\_\-\-R\-E\-P\-L\-Y}!Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!N\-O\-\_\-\-R\-E\-P\-L\-Y@{N\-O\-\_\-\-R\-E\-P\-L\-Y}}\item[{\em +\hypertarget{_modbus_rtu_8h_adf764cbdea00d65edcd07bb9953ad2b7aa04c58a8cc2e7777f6f781e8d51524ae}{N\-O\-\_\-\-R\-E\-P\-L\-Y}\label{_modbus_rtu_8h_adf764cbdea00d65edcd07bb9953ad2b7aa04c58a8cc2e7777f6f781e8d51524ae} +}]\index{E\-X\-C\-\_\-\-F\-U\-N\-C\-\_\-\-C\-O\-D\-E@{E\-X\-C\-\_\-\-F\-U\-N\-C\-\_\-\-C\-O\-D\-E}!Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!E\-X\-C\-\_\-\-F\-U\-N\-C\-\_\-\-C\-O\-D\-E@{E\-X\-C\-\_\-\-F\-U\-N\-C\-\_\-\-C\-O\-D\-E}}\item[{\em +\hypertarget{_modbus_rtu_8h_adf764cbdea00d65edcd07bb9953ad2b7ad82ec66545269170f1401af6e418e8f2}{E\-X\-C\-\_\-\-F\-U\-N\-C\-\_\-\-C\-O\-D\-E}\label{_modbus_rtu_8h_adf764cbdea00d65edcd07bb9953ad2b7ad82ec66545269170f1401af6e418e8f2} +}]\index{E\-X\-C\-\_\-\-A\-D\-D\-R\-\_\-\-R\-A\-N\-G\-E@{E\-X\-C\-\_\-\-A\-D\-D\-R\-\_\-\-R\-A\-N\-G\-E}!Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!E\-X\-C\-\_\-\-A\-D\-D\-R\-\_\-\-R\-A\-N\-G\-E@{E\-X\-C\-\_\-\-A\-D\-D\-R\-\_\-\-R\-A\-N\-G\-E}}\item[{\em +\hypertarget{_modbus_rtu_8h_adf764cbdea00d65edcd07bb9953ad2b7ad3899b13b2069997f5db7f18e9978280}{E\-X\-C\-\_\-\-A\-D\-D\-R\-\_\-\-R\-A\-N\-G\-E}\label{_modbus_rtu_8h_adf764cbdea00d65edcd07bb9953ad2b7ad3899b13b2069997f5db7f18e9978280} +}]\index{E\-X\-C\-\_\-\-R\-E\-G\-S\-\_\-\-Q\-U\-A\-N\-T@{E\-X\-C\-\_\-\-R\-E\-G\-S\-\_\-\-Q\-U\-A\-N\-T}!Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!E\-X\-C\-\_\-\-R\-E\-G\-S\-\_\-\-Q\-U\-A\-N\-T@{E\-X\-C\-\_\-\-R\-E\-G\-S\-\_\-\-Q\-U\-A\-N\-T}}\item[{\em +\hypertarget{_modbus_rtu_8h_adf764cbdea00d65edcd07bb9953ad2b7a062e13fdfefabb1d620506a526be3920}{E\-X\-C\-\_\-\-R\-E\-G\-S\-\_\-\-Q\-U\-A\-N\-T}\label{_modbus_rtu_8h_adf764cbdea00d65edcd07bb9953ad2b7a062e13fdfefabb1d620506a526be3920} +}]\index{E\-X\-C\-\_\-\-E\-X\-E\-C\-U\-T\-E@{E\-X\-C\-\_\-\-E\-X\-E\-C\-U\-T\-E}!Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!E\-X\-C\-\_\-\-E\-X\-E\-C\-U\-T\-E@{E\-X\-C\-\_\-\-E\-X\-E\-C\-U\-T\-E}}\item[{\em +\hypertarget{_modbus_rtu_8h_adf764cbdea00d65edcd07bb9953ad2b7a00e93edc9146c12fd21490d1a0d15f89}{E\-X\-C\-\_\-\-E\-X\-E\-C\-U\-T\-E}\label{_modbus_rtu_8h_adf764cbdea00d65edcd07bb9953ad2b7a00e93edc9146c12fd21490d1a0d15f89} +}]\end{description} +\end{Desc} + + +Definition at line 113 of file Modbus\-Rtu.\-h. + +\hypertarget{_modbus_rtu_8h_a4f165b5bd333856a84635b2594013982}{\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!C\-O\-M\-\_\-\-S\-T\-A\-T\-E\-S@{C\-O\-M\-\_\-\-S\-T\-A\-T\-E\-S}} +\index{C\-O\-M\-\_\-\-S\-T\-A\-T\-E\-S@{C\-O\-M\-\_\-\-S\-T\-A\-T\-E\-S}!ModbusRtu.h@{Modbus\-Rtu.\-h}} +\subsubsection[{C\-O\-M\-\_\-\-S\-T\-A\-T\-E\-S}]{\setlength{\rightskip}{0pt plus 5cm}enum {\bf C\-O\-M\-\_\-\-S\-T\-A\-T\-E\-S}}}\label{_modbus_rtu_8h_a4f165b5bd333856a84635b2594013982} +\begin{Desc} +\item[Enumerator]\par +\begin{description} +\index{C\-O\-M\-\_\-\-I\-D\-L\-E@{C\-O\-M\-\_\-\-I\-D\-L\-E}!Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!C\-O\-M\-\_\-\-I\-D\-L\-E@{C\-O\-M\-\_\-\-I\-D\-L\-E}}\item[{\em +\hypertarget{_modbus_rtu_8h_a4f165b5bd333856a84635b2594013982a3e262bfb13968e43ab8ea55a03ba8b20}{C\-O\-M\-\_\-\-I\-D\-L\-E}\label{_modbus_rtu_8h_a4f165b5bd333856a84635b2594013982a3e262bfb13968e43ab8ea55a03ba8b20} +}]\index{C\-O\-M\-\_\-\-W\-A\-I\-T\-I\-N\-G@{C\-O\-M\-\_\-\-W\-A\-I\-T\-I\-N\-G}!Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!C\-O\-M\-\_\-\-W\-A\-I\-T\-I\-N\-G@{C\-O\-M\-\_\-\-W\-A\-I\-T\-I\-N\-G}}\item[{\em +\hypertarget{_modbus_rtu_8h_a4f165b5bd333856a84635b2594013982ad70b4cc84cc2f21d8b46f73f186dae6b}{C\-O\-M\-\_\-\-W\-A\-I\-T\-I\-N\-G}\label{_modbus_rtu_8h_a4f165b5bd333856a84635b2594013982ad70b4cc84cc2f21d8b46f73f186dae6b} +}]\end{description} +\end{Desc} + + +Definition at line 99 of file Modbus\-Rtu.\-h. + +\hypertarget{_modbus_rtu_8h_a792f00821300f1c7c768db990db646c1}{\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!E\-R\-R\-\_\-\-L\-I\-S\-T@{E\-R\-R\-\_\-\-L\-I\-S\-T}} +\index{E\-R\-R\-\_\-\-L\-I\-S\-T@{E\-R\-R\-\_\-\-L\-I\-S\-T}!ModbusRtu.h@{Modbus\-Rtu.\-h}} +\subsubsection[{E\-R\-R\-\_\-\-L\-I\-S\-T}]{\setlength{\rightskip}{0pt plus 5cm}enum {\bf E\-R\-R\-\_\-\-L\-I\-S\-T}}}\label{_modbus_rtu_8h_a792f00821300f1c7c768db990db646c1} +\begin{Desc} +\item[Enumerator]\par +\begin{description} +\index{E\-R\-R\-\_\-\-N\-O\-T\-\_\-\-M\-A\-S\-T\-E\-R@{E\-R\-R\-\_\-\-N\-O\-T\-\_\-\-M\-A\-S\-T\-E\-R}!Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!E\-R\-R\-\_\-\-N\-O\-T\-\_\-\-M\-A\-S\-T\-E\-R@{E\-R\-R\-\_\-\-N\-O\-T\-\_\-\-M\-A\-S\-T\-E\-R}}\item[{\em +\hypertarget{_modbus_rtu_8h_a792f00821300f1c7c768db990db646c1a12a9ad0aaae512b253a9da9ea19f2b04}{E\-R\-R\-\_\-\-N\-O\-T\-\_\-\-M\-A\-S\-T\-E\-R}\label{_modbus_rtu_8h_a792f00821300f1c7c768db990db646c1a12a9ad0aaae512b253a9da9ea19f2b04} +}]\index{E\-R\-R\-\_\-\-P\-O\-L\-L\-I\-N\-G@{E\-R\-R\-\_\-\-P\-O\-L\-L\-I\-N\-G}!Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!E\-R\-R\-\_\-\-P\-O\-L\-L\-I\-N\-G@{E\-R\-R\-\_\-\-P\-O\-L\-L\-I\-N\-G}}\item[{\em +\hypertarget{_modbus_rtu_8h_a792f00821300f1c7c768db990db646c1a7d2c6c1b333f4b566c613e52b62ab901}{E\-R\-R\-\_\-\-P\-O\-L\-L\-I\-N\-G}\label{_modbus_rtu_8h_a792f00821300f1c7c768db990db646c1a7d2c6c1b333f4b566c613e52b62ab901} +}]\index{E\-R\-R\-\_\-\-B\-U\-F\-F\-\_\-\-O\-V\-E\-R\-F\-L\-O\-W@{E\-R\-R\-\_\-\-B\-U\-F\-F\-\_\-\-O\-V\-E\-R\-F\-L\-O\-W}!Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!E\-R\-R\-\_\-\-B\-U\-F\-F\-\_\-\-O\-V\-E\-R\-F\-L\-O\-W@{E\-R\-R\-\_\-\-B\-U\-F\-F\-\_\-\-O\-V\-E\-R\-F\-L\-O\-W}}\item[{\em +\hypertarget{_modbus_rtu_8h_a792f00821300f1c7c768db990db646c1aafd42890a0ce129e23977fc1aca4044b}{E\-R\-R\-\_\-\-B\-U\-F\-F\-\_\-\-O\-V\-E\-R\-F\-L\-O\-W}\label{_modbus_rtu_8h_a792f00821300f1c7c768db990db646c1aafd42890a0ce129e23977fc1aca4044b} +}]\index{E\-R\-R\-\_\-\-B\-A\-D\-\_\-\-C\-R\-C@{E\-R\-R\-\_\-\-B\-A\-D\-\_\-\-C\-R\-C}!Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!E\-R\-R\-\_\-\-B\-A\-D\-\_\-\-C\-R\-C@{E\-R\-R\-\_\-\-B\-A\-D\-\_\-\-C\-R\-C}}\item[{\em +\hypertarget{_modbus_rtu_8h_a792f00821300f1c7c768db990db646c1a918477ee2e5e31f01b03a83f472b63b0}{E\-R\-R\-\_\-\-B\-A\-D\-\_\-\-C\-R\-C}\label{_modbus_rtu_8h_a792f00821300f1c7c768db990db646c1a918477ee2e5e31f01b03a83f472b63b0} +}]\index{E\-R\-R\-\_\-\-E\-X\-C\-E\-P\-T\-I\-O\-N@{E\-R\-R\-\_\-\-E\-X\-C\-E\-P\-T\-I\-O\-N}!Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!E\-R\-R\-\_\-\-E\-X\-C\-E\-P\-T\-I\-O\-N@{E\-R\-R\-\_\-\-E\-X\-C\-E\-P\-T\-I\-O\-N}}\item[{\em +\hypertarget{_modbus_rtu_8h_a792f00821300f1c7c768db990db646c1ab4be9b5f7e8905633a3c045157f1dd0a}{E\-R\-R\-\_\-\-E\-X\-C\-E\-P\-T\-I\-O\-N}\label{_modbus_rtu_8h_a792f00821300f1c7c768db990db646c1ab4be9b5f7e8905633a3c045157f1dd0a} +}]\end{description} +\end{Desc} + + +Definition at line 105 of file Modbus\-Rtu.\-h. + +\hypertarget{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6}{\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!M\-B\-\_\-\-F\-C@{M\-B\-\_\-\-F\-C}} +\index{M\-B\-\_\-\-F\-C@{M\-B\-\_\-\-F\-C}!ModbusRtu.h@{Modbus\-Rtu.\-h}} +\subsubsection[{M\-B\-\_\-\-F\-C}]{\setlength{\rightskip}{0pt plus 5cm}enum {\bf M\-B\-\_\-\-F\-C}}}\label{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6} + + +\hyperlink{class_modbus}{Modbus} function codes summary. These are the implement function codes either for Master or for Slave. + +\begin{DoxySeeAlso}{See Also} +also \hyperlink{_modbus_rtu_8h_aede21762dc4aa80a14df8dd40ef105f0}{fctsupported} + +also \hyperlink{structmodbus__t}{modbus\-\_\-t} +\end{DoxySeeAlso} +\begin{Desc} +\item[Enumerator]\par +\begin{description} +\index{M\-B\-\_\-\-F\-C\-\_\-\-N\-O\-N\-E@{M\-B\-\_\-\-F\-C\-\_\-\-N\-O\-N\-E}!Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!M\-B\-\_\-\-F\-C\-\_\-\-N\-O\-N\-E@{M\-B\-\_\-\-F\-C\-\_\-\-N\-O\-N\-E}}\item[{\em +\hypertarget{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6a513dc96919a5d5c75f129c1b5b2afea9}{M\-B\-\_\-\-F\-C\-\_\-\-N\-O\-N\-E}\label{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6a513dc96919a5d5c75f129c1b5b2afea9} +}]null operator \index{M\-B\-\_\-\-F\-C\-\_\-\-R\-E\-A\-D\-\_\-\-C\-O\-I\-L\-S@{M\-B\-\_\-\-F\-C\-\_\-\-R\-E\-A\-D\-\_\-\-C\-O\-I\-L\-S}!Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!M\-B\-\_\-\-F\-C\-\_\-\-R\-E\-A\-D\-\_\-\-C\-O\-I\-L\-S@{M\-B\-\_\-\-F\-C\-\_\-\-R\-E\-A\-D\-\_\-\-C\-O\-I\-L\-S}}\item[{\em +\hypertarget{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6a0b2250567e3e0e43522a64cdce637ce0}{M\-B\-\_\-\-F\-C\-\_\-\-R\-E\-A\-D\-\_\-\-C\-O\-I\-L\-S}\label{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6a0b2250567e3e0e43522a64cdce637ce0} +}]F\-C\-T=1 -\/$>$ read coils or digital outputs \index{M\-B\-\_\-\-F\-C\-\_\-\-R\-E\-A\-D\-\_\-\-D\-I\-S\-C\-R\-E\-T\-E\-\_\-\-I\-N\-P\-U\-T@{M\-B\-\_\-\-F\-C\-\_\-\-R\-E\-A\-D\-\_\-\-D\-I\-S\-C\-R\-E\-T\-E\-\_\-\-I\-N\-P\-U\-T}!Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!M\-B\-\_\-\-F\-C\-\_\-\-R\-E\-A\-D\-\_\-\-D\-I\-S\-C\-R\-E\-T\-E\-\_\-\-I\-N\-P\-U\-T@{M\-B\-\_\-\-F\-C\-\_\-\-R\-E\-A\-D\-\_\-\-D\-I\-S\-C\-R\-E\-T\-E\-\_\-\-I\-N\-P\-U\-T}}\item[{\em +\hypertarget{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6ac2b52680d6c0bbe3d3e0e9ec7a88fc2e}{M\-B\-\_\-\-F\-C\-\_\-\-R\-E\-A\-D\-\_\-\-D\-I\-S\-C\-R\-E\-T\-E\-\_\-\-I\-N\-P\-U\-T}\label{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6ac2b52680d6c0bbe3d3e0e9ec7a88fc2e} +}]F\-C\-T=2 -\/$>$ read digital inputs \index{M\-B\-\_\-\-F\-C\-\_\-\-R\-E\-A\-D\-\_\-\-R\-E\-G\-I\-S\-T\-E\-R\-S@{M\-B\-\_\-\-F\-C\-\_\-\-R\-E\-A\-D\-\_\-\-R\-E\-G\-I\-S\-T\-E\-R\-S}!Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!M\-B\-\_\-\-F\-C\-\_\-\-R\-E\-A\-D\-\_\-\-R\-E\-G\-I\-S\-T\-E\-R\-S@{M\-B\-\_\-\-F\-C\-\_\-\-R\-E\-A\-D\-\_\-\-R\-E\-G\-I\-S\-T\-E\-R\-S}}\item[{\em +\hypertarget{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6a0c6066cf0a67a1bb349da35ef31e4e8f}{M\-B\-\_\-\-F\-C\-\_\-\-R\-E\-A\-D\-\_\-\-R\-E\-G\-I\-S\-T\-E\-R\-S}\label{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6a0c6066cf0a67a1bb349da35ef31e4e8f} +}]F\-C\-T=3 -\/$>$ read registers or analog outputs \index{M\-B\-\_\-\-F\-C\-\_\-\-R\-E\-A\-D\-\_\-\-I\-N\-P\-U\-T\-\_\-\-R\-E\-G\-I\-S\-T\-E\-R@{M\-B\-\_\-\-F\-C\-\_\-\-R\-E\-A\-D\-\_\-\-I\-N\-P\-U\-T\-\_\-\-R\-E\-G\-I\-S\-T\-E\-R}!Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!M\-B\-\_\-\-F\-C\-\_\-\-R\-E\-A\-D\-\_\-\-I\-N\-P\-U\-T\-\_\-\-R\-E\-G\-I\-S\-T\-E\-R@{M\-B\-\_\-\-F\-C\-\_\-\-R\-E\-A\-D\-\_\-\-I\-N\-P\-U\-T\-\_\-\-R\-E\-G\-I\-S\-T\-E\-R}}\item[{\em +\hypertarget{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6a9b2d4a3fb96e4af559d5330ad0c01c07}{M\-B\-\_\-\-F\-C\-\_\-\-R\-E\-A\-D\-\_\-\-I\-N\-P\-U\-T\-\_\-\-R\-E\-G\-I\-S\-T\-E\-R}\label{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6a9b2d4a3fb96e4af559d5330ad0c01c07} +}]F\-C\-T=4 -\/$>$ read analog inputs \index{M\-B\-\_\-\-F\-C\-\_\-\-W\-R\-I\-T\-E\-\_\-\-C\-O\-I\-L@{M\-B\-\_\-\-F\-C\-\_\-\-W\-R\-I\-T\-E\-\_\-\-C\-O\-I\-L}!Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!M\-B\-\_\-\-F\-C\-\_\-\-W\-R\-I\-T\-E\-\_\-\-C\-O\-I\-L@{M\-B\-\_\-\-F\-C\-\_\-\-W\-R\-I\-T\-E\-\_\-\-C\-O\-I\-L}}\item[{\em +\hypertarget{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6a90126d6c25fb5711c103e819ccda01c7}{M\-B\-\_\-\-F\-C\-\_\-\-W\-R\-I\-T\-E\-\_\-\-C\-O\-I\-L}\label{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6a90126d6c25fb5711c103e819ccda01c7} +}]F\-C\-T=5 -\/$>$ write single coil or output \index{M\-B\-\_\-\-F\-C\-\_\-\-W\-R\-I\-T\-E\-\_\-\-R\-E\-G\-I\-S\-T\-E\-R@{M\-B\-\_\-\-F\-C\-\_\-\-W\-R\-I\-T\-E\-\_\-\-R\-E\-G\-I\-S\-T\-E\-R}!Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!M\-B\-\_\-\-F\-C\-\_\-\-W\-R\-I\-T\-E\-\_\-\-R\-E\-G\-I\-S\-T\-E\-R@{M\-B\-\_\-\-F\-C\-\_\-\-W\-R\-I\-T\-E\-\_\-\-R\-E\-G\-I\-S\-T\-E\-R}}\item[{\em +\hypertarget{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6a74e1ffd48177f0e7e33c2c968a1bd86f}{M\-B\-\_\-\-F\-C\-\_\-\-W\-R\-I\-T\-E\-\_\-\-R\-E\-G\-I\-S\-T\-E\-R}\label{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6a74e1ffd48177f0e7e33c2c968a1bd86f} +}]F\-C\-T=6 -\/$>$ write single register \index{M\-B\-\_\-\-F\-C\-\_\-\-W\-R\-I\-T\-E\-\_\-\-M\-U\-L\-T\-I\-P\-L\-E\-\_\-\-C\-O\-I\-L\-S@{M\-B\-\_\-\-F\-C\-\_\-\-W\-R\-I\-T\-E\-\_\-\-M\-U\-L\-T\-I\-P\-L\-E\-\_\-\-C\-O\-I\-L\-S}!Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!M\-B\-\_\-\-F\-C\-\_\-\-W\-R\-I\-T\-E\-\_\-\-M\-U\-L\-T\-I\-P\-L\-E\-\_\-\-C\-O\-I\-L\-S@{M\-B\-\_\-\-F\-C\-\_\-\-W\-R\-I\-T\-E\-\_\-\-M\-U\-L\-T\-I\-P\-L\-E\-\_\-\-C\-O\-I\-L\-S}}\item[{\em +\hypertarget{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6ac69c42d25cbc0ef303de57bd3d0e2304}{M\-B\-\_\-\-F\-C\-\_\-\-W\-R\-I\-T\-E\-\_\-\-M\-U\-L\-T\-I\-P\-L\-E\-\_\-\-C\-O\-I\-L\-S}\label{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6ac69c42d25cbc0ef303de57bd3d0e2304} +}]F\-C\-T=15 -\/$>$ write multiple coils or outputs \index{M\-B\-\_\-\-F\-C\-\_\-\-W\-R\-I\-T\-E\-\_\-\-M\-U\-L\-T\-I\-P\-L\-E\-\_\-\-R\-E\-G\-I\-S\-T\-E\-R\-S@{M\-B\-\_\-\-F\-C\-\_\-\-W\-R\-I\-T\-E\-\_\-\-M\-U\-L\-T\-I\-P\-L\-E\-\_\-\-R\-E\-G\-I\-S\-T\-E\-R\-S}!Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!M\-B\-\_\-\-F\-C\-\_\-\-W\-R\-I\-T\-E\-\_\-\-M\-U\-L\-T\-I\-P\-L\-E\-\_\-\-R\-E\-G\-I\-S\-T\-E\-R\-S@{M\-B\-\_\-\-F\-C\-\_\-\-W\-R\-I\-T\-E\-\_\-\-M\-U\-L\-T\-I\-P\-L\-E\-\_\-\-R\-E\-G\-I\-S\-T\-E\-R\-S}}\item[{\em +\hypertarget{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6a2ccdcde4f07865ffb47fbea0a01026bb}{M\-B\-\_\-\-F\-C\-\_\-\-W\-R\-I\-T\-E\-\_\-\-M\-U\-L\-T\-I\-P\-L\-E\-\_\-\-R\-E\-G\-I\-S\-T\-E\-R\-S}\label{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6a2ccdcde4f07865ffb47fbea0a01026bb} +}]F\-C\-T=16 -\/$>$ write multiple registers \end{description} +\end{Desc} + + +Definition at line 87 of file Modbus\-Rtu.\-h. + +\hypertarget{_modbus_rtu_8h_aa9996e8b4648c78acf6cde2401e230ba}{\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!M\-E\-S\-S\-A\-G\-E@{M\-E\-S\-S\-A\-G\-E}} +\index{M\-E\-S\-S\-A\-G\-E@{M\-E\-S\-S\-A\-G\-E}!ModbusRtu.h@{Modbus\-Rtu.\-h}} +\subsubsection[{M\-E\-S\-S\-A\-G\-E}]{\setlength{\rightskip}{0pt plus 5cm}enum {\bf M\-E\-S\-S\-A\-G\-E}}}\label{_modbus_rtu_8h_aa9996e8b4648c78acf6cde2401e230ba} + + +Indexes to telegram frame positions. + +\begin{Desc} +\item[Enumerator]\par +\begin{description} +\index{I\-D@{I\-D}!Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!I\-D@{I\-D}}\item[{\em +\hypertarget{_modbus_rtu_8h_aa9996e8b4648c78acf6cde2401e230baa001479a58fb44c39a29b20d565081a68}{I\-D}\label{_modbus_rtu_8h_aa9996e8b4648c78acf6cde2401e230baa001479a58fb44c39a29b20d565081a68} +}]I\-D field. \index{F\-U\-N\-C@{F\-U\-N\-C}!Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!F\-U\-N\-C@{F\-U\-N\-C}}\item[{\em +\hypertarget{_modbus_rtu_8h_aa9996e8b4648c78acf6cde2401e230baa389e03ce61ac2d93fd54069187ab58af}{F\-U\-N\-C}\label{_modbus_rtu_8h_aa9996e8b4648c78acf6cde2401e230baa389e03ce61ac2d93fd54069187ab58af} +}]Function code position. \index{A\-D\-D\-\_\-\-H\-I@{A\-D\-D\-\_\-\-H\-I}!Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!A\-D\-D\-\_\-\-H\-I@{A\-D\-D\-\_\-\-H\-I}}\item[{\em +\hypertarget{_modbus_rtu_8h_aa9996e8b4648c78acf6cde2401e230baad19e7653c9276b91fb590af017de192c}{A\-D\-D\-\_\-\-H\-I}\label{_modbus_rtu_8h_aa9996e8b4648c78acf6cde2401e230baad19e7653c9276b91fb590af017de192c} +}]Address high byte. \index{A\-D\-D\-\_\-\-L\-O@{A\-D\-D\-\_\-\-L\-O}!Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!A\-D\-D\-\_\-\-L\-O@{A\-D\-D\-\_\-\-L\-O}}\item[{\em +\hypertarget{_modbus_rtu_8h_aa9996e8b4648c78acf6cde2401e230baa2cbdff2e20e58233096845bf42acc97c}{A\-D\-D\-\_\-\-L\-O}\label{_modbus_rtu_8h_aa9996e8b4648c78acf6cde2401e230baa2cbdff2e20e58233096845bf42acc97c} +}]Address low byte. \index{N\-B\-\_\-\-H\-I@{N\-B\-\_\-\-H\-I}!Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!N\-B\-\_\-\-H\-I@{N\-B\-\_\-\-H\-I}}\item[{\em +\hypertarget{_modbus_rtu_8h_aa9996e8b4648c78acf6cde2401e230baa61f961bb4614db2fc51125331f79a9d6}{N\-B\-\_\-\-H\-I}\label{_modbus_rtu_8h_aa9996e8b4648c78acf6cde2401e230baa61f961bb4614db2fc51125331f79a9d6} +}]Number of coils or registers high byte. \index{N\-B\-\_\-\-L\-O@{N\-B\-\_\-\-L\-O}!Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!N\-B\-\_\-\-L\-O@{N\-B\-\_\-\-L\-O}}\item[{\em +\hypertarget{_modbus_rtu_8h_aa9996e8b4648c78acf6cde2401e230baa22b2a3a58501a5bbe69ef569aa7fb30f}{N\-B\-\_\-\-L\-O}\label{_modbus_rtu_8h_aa9996e8b4648c78acf6cde2401e230baa22b2a3a58501a5bbe69ef569aa7fb30f} +}]Number of coils or registers low byte. \index{B\-Y\-T\-E\-\_\-\-C\-N\-T@{B\-Y\-T\-E\-\_\-\-C\-N\-T}!Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}}\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!B\-Y\-T\-E\-\_\-\-C\-N\-T@{B\-Y\-T\-E\-\_\-\-C\-N\-T}}\item[{\em +\hypertarget{_modbus_rtu_8h_aa9996e8b4648c78acf6cde2401e230baaf84036e1dd68a2e160c3394fc083e892}{B\-Y\-T\-E\-\_\-\-C\-N\-T}\label{_modbus_rtu_8h_aa9996e8b4648c78acf6cde2401e230baaf84036e1dd68a2e160c3394fc083e892} +}]byte counter \end{description} +\end{Desc} + + +Definition at line 68 of file Modbus\-Rtu.\-h. + + + +\subsection{Variable Documentation} +\hypertarget{_modbus_rtu_8h_aede21762dc4aa80a14df8dd40ef105f0}{\index{Modbus\-Rtu.\-h@{Modbus\-Rtu.\-h}!fctsupported@{fctsupported}} +\index{fctsupported@{fctsupported}!ModbusRtu.h@{Modbus\-Rtu.\-h}} +\subsubsection[{fctsupported}]{\setlength{\rightskip}{0pt plus 5cm}const unsigned char fctsupported\mbox{[}$\,$\mbox{]}}}\label{_modbus_rtu_8h_aede21762dc4aa80a14df8dd40ef105f0} +{\bfseries Initial value\-:} +\begin{DoxyCode} += \{ + \hyperlink{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6a0b2250567e3e0e43522a64cdce637ce0}{MB\_FC\_READ\_COILS}, + \hyperlink{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6ac2b52680d6c0bbe3d3e0e9ec7a88fc2e}{MB\_FC\_READ\_DISCRETE\_INPUT}, + \hyperlink{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6a0c6066cf0a67a1bb349da35ef31e4e8f}{MB\_FC\_READ\_REGISTERS}, + \hyperlink{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6a9b2d4a3fb96e4af559d5330ad0c01c07}{MB\_FC\_READ\_INPUT\_REGISTER}, + \hyperlink{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6a90126d6c25fb5711c103e819ccda01c7}{MB\_FC\_WRITE\_COIL}, + \hyperlink{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6a74e1ffd48177f0e7e33c2c968a1bd86f}{MB\_FC\_WRITE\_REGISTER}, + \hyperlink{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6ac69c42d25cbc0ef303de57bd3d0e2304}{MB\_FC\_WRITE\_MULTIPLE\_COILS}, + \hyperlink{_modbus_rtu_8h_aff1341ea5077cc6097a0d7db89be4cf6a2ccdcde4f07865ffb47fbea0a01026bb}{MB\_FC\_WRITE\_MULTIPLE\_REGISTERS} +\} +\end{DoxyCode} + + +Definition at line 121 of file Modbus\-Rtu.\-h. + diff --git a/software/firmware/libraries/modbus/documentation/latex/annotated.tex b/software/firmware/libraries/modbus/documentation/latex/annotated.tex new file mode 100644 index 0000000..5674754 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/latex/annotated.tex @@ -0,0 +1,5 @@ +\section{Class List} +Here are the classes, structs, unions and interfaces with brief descriptions\-:\begin{DoxyCompactList} +\item\contentsline{section}{\hyperlink{class_modbus}{Modbus} \\*Arduino class library for communicating with \hyperlink{class_modbus}{Modbus} devices over U\-S\-B/\-R\-S232/485 (via R\-T\-U protocol) }{\pageref{class_modbus}}{} +\item\contentsline{section}{\hyperlink{structmodbus__t}{modbus\-\_\-t} \\*Master query structure\-: This includes all the necessary fields to make the Master generate a \hyperlink{class_modbus}{Modbus} query. A Master may keep several of these structures and send them cyclically or use them according to program needs }{\pageref{structmodbus__t}}{} +\end{DoxyCompactList} diff --git a/software/firmware/libraries/modbus/documentation/latex/class_modbus.tex b/software/firmware/libraries/modbus/documentation/latex/class_modbus.tex new file mode 100644 index 0000000..2655e3f --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/latex/class_modbus.tex @@ -0,0 +1,129 @@ +\hypertarget{class_modbus}{\section{Modbus Class Reference} +\label{class_modbus}\index{Modbus@{Modbus}} +} + + +Arduino class library for communicating with \hyperlink{class_modbus}{Modbus} devices over U\-S\-B/\-R\-S232/485 (via R\-T\-U protocol). + + + + +{\ttfamily \#include $<$Modbus\-Rtu.\-h$>$} + +\subsection*{Public Member Functions} +\begin{DoxyCompactItemize} +\item +\hyperlink{group__setup_ga101809cdd4734537bab58dc315a840b4}{Modbus} () +\begin{DoxyCompactList}\small\item\em Default Constructor for Master through Serial. \end{DoxyCompactList}\item +\hyperlink{class_modbus_afbbf7c81565d8e1ea1cd5890a96e7507}{Modbus} (uint8\-\_\-t u8id, uint8\-\_\-t u8serno) +\item +\hyperlink{class_modbus_a5e23a7b669d0c2d5be1c0054c7c54dca}{Modbus} (uint8\-\_\-t u8id, uint8\-\_\-t u8serno, uint8\-\_\-t u8txenpin) +\item +void \hyperlink{group__setup_ga475a4fa0fac491307b10c4529ad6d2a0}{begin} (long u32speed) +\begin{DoxyCompactList}\small\item\em Initialize class object. \end{DoxyCompactList}\item +void \hyperlink{class_modbus_a4f9673a3d113c49af69cb87b030ef099}{begin} () +\item +void \hyperlink{group__setup_gaf828190ebe24efb1b3b1957429f3872e}{set\-Time\-Out} (uint16\-\_\-t u16timeout) +\begin{DoxyCompactList}\small\item\em write communication watch-\/dog timer \end{DoxyCompactList}\item +uint16\-\_\-t \hyperlink{class_modbus_ac860024db3117a2ef907d0325b2fb7a1}{get\-Time\-Out} () +\begin{DoxyCompactList}\small\item\em get communication watch-\/dog timer value \end{DoxyCompactList}\item +boolean \hyperlink{group__loop_gaf6dd413191ed8a833022046873e0a063}{get\-Time\-Out\-State} () +\begin{DoxyCompactList}\small\item\em get communication watch-\/dog timer state \end{DoxyCompactList}\item +int8\-\_\-t \hyperlink{group__loop_ga19398cabed57b6d085d014af6c149f54}{query} (\hyperlink{structmodbus__t}{modbus\-\_\-t} telegram) +\begin{DoxyCompactList}\small\item\em only for master \end{DoxyCompactList}\item +int8\-\_\-t \hyperlink{group__loop_ga53bde78490c1cd8e3c070a676bdcfb0d}{poll} () +\begin{DoxyCompactList}\small\item\em cyclic poll for master \end{DoxyCompactList}\item +int8\-\_\-t \hyperlink{group__loop_gab3ef20562fc8cee14fc85f7e276890b5}{poll} (uint16\-\_\-t $\ast$regs, uint8\-\_\-t u8size) +\begin{DoxyCompactList}\small\item\em cyclic poll for slave \end{DoxyCompactList}\item +uint16\-\_\-t \hyperlink{group__buffer_ga4fa6ede8df85b7cc70b1282b9547378a}{get\-In\-Cnt} () +\begin{DoxyCompactList}\small\item\em number of incoming messages \end{DoxyCompactList}\item +uint16\-\_\-t \hyperlink{group__buffer_ga6f831ecaf3678c27dafb663a28bf81f0}{get\-Out\-Cnt} () +\begin{DoxyCompactList}\small\item\em number of outcoming messages \end{DoxyCompactList}\item +uint16\-\_\-t \hyperlink{group__buffer_ga6883c7f3ff12f084ed56d559d4e06ed0}{get\-Err\-Cnt} () +\begin{DoxyCompactList}\small\item\em error counter \end{DoxyCompactList}\item +uint8\-\_\-t \hyperlink{group__setup_ga6449894306ff8cc5d4caff09b1b0d1ce}{get\-I\-D} () +\begin{DoxyCompactList}\small\item\em get slave I\-D between 1 and 247 \end{DoxyCompactList}\item +uint8\-\_\-t \hyperlink{group__buffer_ga2f39717d957a929af488c9120488fcdc}{get\-State} () +\item +uint8\-\_\-t \hyperlink{group__buffer_gace7f726db13adc8feeceab987b719531}{get\-Last\-Error} () +\begin{DoxyCompactList}\small\item\em get last error message \end{DoxyCompactList}\item +void \hyperlink{group__setup_ga9bd497e97ac1777d4f0d4171078d60e0}{set\-I\-D} (uint8\-\_\-t u8id) +\begin{DoxyCompactList}\small\item\em write new I\-D for the slave \end{DoxyCompactList}\item +void \hyperlink{class_modbus_a0d80101b650344c712a085c4bb005c4c}{end} () +\begin{DoxyCompactList}\small\item\em finish any communication and release serial communication port \end{DoxyCompactList}\end{DoxyCompactItemize} + + +\subsection{Detailed Description} +Arduino class library for communicating with \hyperlink{class_modbus}{Modbus} devices over U\-S\-B/\-R\-S232/485 (via R\-T\-U protocol). + +Definition at line 141 of file Modbus\-Rtu.\-h. + + + +\subsection{Constructor \& Destructor Documentation} +\hypertarget{class_modbus_afbbf7c81565d8e1ea1cd5890a96e7507}{\index{Modbus@{Modbus}!Modbus@{Modbus}} +\index{Modbus@{Modbus}!Modbus@{Modbus}} +\subsubsection[{Modbus}]{\setlength{\rightskip}{0pt plus 5cm}Modbus\-::\-Modbus ( +\begin{DoxyParamCaption} +\item[{uint8\-\_\-t}]{u8id, } +\item[{uint8\-\_\-t}]{u8serno} +\end{DoxyParamCaption} +)}}\label{class_modbus_afbbf7c81565d8e1ea1cd5890a96e7507} + + +Definition at line 218 of file Modbus\-Rtu.\-h. + +\hypertarget{class_modbus_a5e23a7b669d0c2d5be1c0054c7c54dca}{\index{Modbus@{Modbus}!Modbus@{Modbus}} +\index{Modbus@{Modbus}!Modbus@{Modbus}} +\subsubsection[{Modbus}]{\setlength{\rightskip}{0pt plus 5cm}Modbus\-::\-Modbus ( +\begin{DoxyParamCaption} +\item[{uint8\-\_\-t}]{u8id, } +\item[{uint8\-\_\-t}]{u8serno, } +\item[{uint8\-\_\-t}]{u8txenpin} +\end{DoxyParamCaption} +)}}\label{class_modbus_a5e23a7b669d0c2d5be1c0054c7c54dca} + + +Definition at line 234 of file Modbus\-Rtu.\-h. + + + +\subsection{Member Function Documentation} +\hypertarget{class_modbus_a4f9673a3d113c49af69cb87b030ef099}{\index{Modbus@{Modbus}!begin@{begin}} +\index{begin@{begin}!Modbus@{Modbus}} +\subsubsection[{begin}]{\setlength{\rightskip}{0pt plus 5cm}void Modbus\-::begin ( +\begin{DoxyParamCaption} +{} +\end{DoxyParamCaption} +)}}\label{class_modbus_a4f9673a3d113c49af69cb87b030ef099} + + +Definition at line 299 of file Modbus\-Rtu.\-h. + +\hypertarget{class_modbus_a0d80101b650344c712a085c4bb005c4c}{\index{Modbus@{Modbus}!end@{end}} +\index{end@{end}!Modbus@{Modbus}} +\subsubsection[{end}]{\setlength{\rightskip}{0pt plus 5cm}void Modbus\-::end ( +\begin{DoxyParamCaption} +{} +\end{DoxyParamCaption} +)}}\label{class_modbus_a0d80101b650344c712a085c4bb005c4c} + + +finish any communication and release serial communication port + +\hypertarget{class_modbus_ac860024db3117a2ef907d0325b2fb7a1}{\index{Modbus@{Modbus}!get\-Time\-Out@{get\-Time\-Out}} +\index{get\-Time\-Out@{get\-Time\-Out}!Modbus@{Modbus}} +\subsubsection[{get\-Time\-Out}]{\setlength{\rightskip}{0pt plus 5cm}uint16\-\_\-t Modbus\-::get\-Time\-Out ( +\begin{DoxyParamCaption} +{} +\end{DoxyParamCaption} +)}}\label{class_modbus_ac860024db3117a2ef907d0325b2fb7a1} + + +get communication watch-\/dog timer value + + + +The documentation for this class was generated from the following file\-:\begin{DoxyCompactItemize} +\item +\hyperlink{_modbus_rtu_8h}{Modbus\-Rtu.\-h}\end{DoxyCompactItemize} diff --git a/software/firmware/libraries/modbus/documentation/latex/doxygen.sty b/software/firmware/libraries/modbus/documentation/latex/doxygen.sty new file mode 100644 index 0000000..199abf8 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/latex/doxygen.sty @@ -0,0 +1,464 @@ +\NeedsTeXFormat{LaTeX2e} +\ProvidesPackage{doxygen} + +% Packages used by this style file +\RequirePackage{alltt} +\RequirePackage{array} +\RequirePackage{calc} +\RequirePackage{float} +\RequirePackage{ifthen} +\RequirePackage{verbatim} +\RequirePackage[table]{xcolor} +\RequirePackage{xtab} + +%---------- Internal commands used in this style file ---------------- + +\newcommand{\ensurespace}[1]{% + \begingroup% + \setlength{\dimen@}{#1}% + \vskip\z@\@plus\dimen@% + \penalty -100\vskip\z@\@plus -\dimen@% + \vskip\dimen@% + \penalty 9999% + \vskip -\dimen@% + \vskip\z@skip% hide the previous |\vskip| from |\addvspace| + \endgroup% +} + +\newcommand{\DoxyLabelFont}{} +\newcommand{\entrylabel}[1]{% + {% + \parbox[b]{\labelwidth-4pt}{% + \makebox[0pt][l]{\DoxyLabelFont#1}% + \vspace{1.5\baselineskip}% + }% + }% +} + +\newenvironment{DoxyDesc}[1]{% + \ensurespace{4\baselineskip}% + \begin{list}{}{% + \settowidth{\labelwidth}{20pt}% + \setlength{\parsep}{0pt}% + \setlength{\itemsep}{0pt}% + \setlength{\leftmargin}{\labelwidth+\labelsep}% + \renewcommand{\makelabel}{\entrylabel}% + }% + \item[#1]% +}{% + \end{list}% +} + +\newsavebox{\xrefbox} +\newlength{\xreflength} +\newcommand{\xreflabel}[1]{% + \sbox{\xrefbox}{#1}% + \setlength{\xreflength}{\wd\xrefbox}% + \ifthenelse{\xreflength>\labelwidth}{% + \begin{minipage}{\textwidth}% + \setlength{\parindent}{0pt}% + \hangindent=15pt\bfseries #1\vspace{1.2\itemsep}% + \end{minipage}% + }{% + \parbox[b]{\labelwidth}{\makebox[0pt][l]{\textbf{#1}}}% + }% +} + +%---------- Commands used by doxygen LaTeX output generator ---------- + +% Used by
 ... 
+\newenvironment{DoxyPre}{% + \small% + \begin{alltt}% +}{% + \end{alltt}% + \normalsize% +} + +% Used by @code ... @endcode +\newenvironment{DoxyCode}{% + \par% + \scriptsize% + \begin{alltt}% +}{% + \end{alltt}% + \normalsize% +} + +% Used by @example, @include, @includelineno and @dontinclude +\newenvironment{DoxyCodeInclude}{% + \DoxyCode% +}{% + \endDoxyCode% +} + +% Used by @verbatim ... @endverbatim +\newenvironment{DoxyVerb}{% + \footnotesize% + \verbatim% +}{% + \endverbatim% + \normalsize% +} + +% Used by @verbinclude +\newenvironment{DoxyVerbInclude}{% + \DoxyVerb% +}{% + \endDoxyVerb% +} + +% Used by numbered lists (using '-#' or
    ...
) +\newenvironment{DoxyEnumerate}{% + \enumerate% +}{% + \endenumerate% +} + +% Used by bullet lists (using '-', @li, @arg, or
    ...
) +\newenvironment{DoxyItemize}{% + \itemize% +}{% + \enditemize% +} + +% Used by description lists (using
...
) +\newenvironment{DoxyDescription}{% + \description% +}{% + \enddescription% +} + +% Used by @image, @dotfile, @dot ... @enddot, and @msc ... @endmsc +% (only if caption is specified) +\newenvironment{DoxyImage}{% + \begin{figure}[H]% + \begin{center}% +}{% + \end{center}% + \end{figure}% +} + +% Used by @image, @dotfile, @dot ... @enddot, and @msc ... @endmsc +% (only if no caption is specified) +\newenvironment{DoxyImageNoCaption}{% +}{% +} + +% Used by @attention +\newenvironment{DoxyAttention}[1]{% + \begin{DoxyDesc}{#1}% +}{% + \end{DoxyDesc}% +} + +% Used by @author and @authors +\newenvironment{DoxyAuthor}[1]{% + \begin{DoxyDesc}{#1}% +}{% + \end{DoxyDesc}% +} + +% Used by @date +\newenvironment{DoxyDate}[1]{% + \begin{DoxyDesc}{#1}% +}{% + \end{DoxyDesc}% +} + +% Used by @invariant +\newenvironment{DoxyInvariant}[1]{% + \begin{DoxyDesc}{#1}% +}{% + \end{DoxyDesc}% +} + +% Used by @note +\newenvironment{DoxyNote}[1]{% + \begin{DoxyDesc}{#1}% +}{% + \end{DoxyDesc}% +} + +% Used by @post +\newenvironment{DoxyPostcond}[1]{% + \begin{DoxyDesc}{#1}% +}{% + \end{DoxyDesc}% +} + +% Used by @pre +\newenvironment{DoxyPrecond}[1]{% + \begin{DoxyDesc}{#1}% +}{% + \end{DoxyDesc}% +} + +% Used by @copyright +\newenvironment{DoxyCopyright}[1]{% + \begin{DoxyDesc}{#1}% +}{% + \end{DoxyDesc}% +} + +% Used by @remark +\newenvironment{DoxyRemark}[1]{% + \begin{DoxyDesc}{#1}% +}{% + \end{DoxyDesc}% +} + +% Used by @return and @returns +\newenvironment{DoxyReturn}[1]{% + \begin{DoxyDesc}{#1}% +}{% + \end{DoxyDesc}% +} + +% Used by @since +\newenvironment{DoxySince}[1]{% + \begin{DoxyDesc}{#1}% +}{% + \end{DoxyDesc}% +} + +% Used by @see +\newenvironment{DoxySeeAlso}[1]{% + \begin{DoxyDesc}{#1}% +}{% + \end{DoxyDesc}% +} + +% Used by @version +\newenvironment{DoxyVersion}[1]{% + \begin{DoxyDesc}{#1}% +}{% + \end{DoxyDesc}% +} + +% Used by @warning +\newenvironment{DoxyWarning}[1]{% + \begin{DoxyDesc}{#1}% +}{% + \end{DoxyDesc}% +} + +% Used by @internal +\newenvironment{DoxyInternal}[1]{% + \paragraph*{#1}% +}{% +} + +% Used by @par and @paragraph +\newenvironment{DoxyParagraph}[1]{% + \begin{list}{}{% + \settowidth{\labelwidth}{40pt}% + \setlength{\leftmargin}{\labelwidth}% + \setlength{\parsep}{0pt}% + \setlength{\itemsep}{-4pt}% + \renewcommand{\makelabel}{\entrylabel}% + }% + \item[#1]% +}{% + \end{list}% +} + +% Used by parameter lists +\newenvironment{DoxyParams}[2][]{% + \par% + \tabletail{\hline}% + \tablelasttail{\hline}% + \tablefirsthead{}% + \tablehead{}% + \ifthenelse{\equal{#1}{}}% + {\tablefirsthead{\multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #2}\\[1ex]}% + \begin{xtabular}{|>{\raggedleft\hspace{0pt}}p{0.15\textwidth}|% + p{0.805\textwidth}|}}% + {\ifthenelse{\equal{#1}{1}}% + {\tablefirsthead{\multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #2}\\[1ex]}% + \begin{xtabular}{|>{\centering}p{0.10\textwidth}|% + >{\raggedleft\hspace{0pt}}p{0.15\textwidth}|% + p{0.678\textwidth}|}}% + {\tablefirsthead{\multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #2}\\[1ex]}% + \begin{xtabular}{|>{\centering}p{0.10\textwidth}|% + >{\centering\hspace{0pt}}p{0.15\textwidth}|% + >{\raggedleft\hspace{0pt}}p{0.15\textwidth}|% + p{0.501\textwidth}|}}% + }\hline% +}{% + \end{xtabular}% + \tablefirsthead{}% + \vspace{6pt}% +} + +% Used for fields of simple structs +\newenvironment{DoxyFields}[1]{% + \par% + \tabletail{\hline}% + \tablelasttail{\hline}% + \tablehead{}% + \tablefirsthead{\multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]}% + \begin{xtabular}{|>{\raggedleft\hspace{0pt}}p{0.15\textwidth}|% + p{0.15\textwidth}|% + p{0.63\textwidth}|}% + \hline% +}{% + \end{xtabular}% + \tablefirsthead{}% + \vspace{6pt}% +} + +% Used for parameters within a detailed function description +\newenvironment{DoxyParamCaption}{% + \renewcommand{\item}[2][]{##1 {\em ##2}}% +}{% +} + +% Used by return value lists +\newenvironment{DoxyRetVals}[1]{% + \par% + \tabletail{\hline}% + \tablelasttail{\hline}% + \tablehead{}% + \tablefirsthead{\multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]}% + \begin{xtabular}{|>{\raggedleft\hspace{0pt}}p{0.25\textwidth}|% + p{0.705\textwidth}|}% + \hline% +}{% + \end{xtabular}% + \tablefirsthead{}% + \vspace{6pt}% +} + +% Used by exception lists +\newenvironment{DoxyExceptions}[1]{% + \par% + \tabletail{\hline}% + \tablelasttail{\hline}% + \tablehead{}% + \tablefirsthead{\multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]}% + \begin{xtabular}{|>{\raggedleft\hspace{0pt}}p{0.25\textwidth}|% + p{0.705\textwidth}|}% + \hline% +}{% + \end{xtabular}% + \tablefirsthead{}% + \vspace{6pt}% +} + +% Used by template parameter lists +\newenvironment{DoxyTemplParams}[1]{% + \par% + \tabletail{\hline}% + \tablelasttail{\hline}% + \tablehead{}% + \tablefirsthead{\multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]}% + \begin{xtabular}{|>{\raggedleft\hspace{0pt}}p{0.25\textwidth}|% + p{0.705\textwidth}|}% + \hline% +}{% + \end{xtabular}% + \tablefirsthead{}% + \vspace{6pt}% +} + +% Used for member lists +\newenvironment{DoxyCompactItemize}{% + \begin{itemize}% + \setlength{\itemsep}{-3pt}% + \setlength{\parsep}{0pt}% + \setlength{\topsep}{0pt}% + \setlength{\partopsep}{0pt}% +}{% + \end{itemize}% +} + +% Used for member descriptions +\newenvironment{DoxyCompactList}{% + \begin{list}{}{% + \setlength{\leftmargin}{0.5cm}% + \setlength{\itemsep}{0pt}% + \setlength{\parsep}{0pt}% + \setlength{\topsep}{0pt}% + \renewcommand{\makelabel}{\hfill}% + }% +}{% + \end{list}% +} + +% Used for reference lists (@bug, @deprecated, @todo, etc.) +\newenvironment{DoxyRefList}{% + \begin{list}{}{% + \setlength{\labelwidth}{10pt}% + \setlength{\leftmargin}{\labelwidth}% + \addtolength{\leftmargin}{\labelsep}% + \renewcommand{\makelabel}{\xreflabel}% + }% +}{% + \end{list}% +} + +% Used by @bug, @deprecated, @todo, etc. +\newenvironment{DoxyRefDesc}[1]{% + \begin{list}{}{% + \renewcommand\makelabel[1]{\textbf{##1}}% + \settowidth\labelwidth{\makelabel{#1}}% + \setlength\leftmargin{\labelwidth+\labelsep}% + }% +}{% + \end{list}% +} + +% Used by parameter lists and simple sections +\newenvironment{Desc} +{\begin{list}{}{% + \settowidth{\labelwidth}{40pt}% + \setlength{\leftmargin}{\labelwidth}% + \setlength{\parsep}{0pt}% + \setlength{\itemsep}{-4pt}% + \renewcommand{\makelabel}{\entrylabel}% + } +}{% + \end{list}% +} + +% Used by tables +\newcommand{\PBS}[1]{\let\temp=\\#1\let\\=\temp}% +\newlength{\tmplength}% +\newenvironment{TabularC}[1]% +{% +\setlength{\tmplength}% + {\linewidth/(#1)-\tabcolsep*2-\arrayrulewidth*(#1+1)/(#1)}% + \par\begin{xtabular*}{\linewidth}% + {*{#1}{|>{\PBS\raggedright\hspace{0pt}}p{\the\tmplength}}|}% +}% +{\end{xtabular*}\par}% + +% Used for member group headers +\newenvironment{Indent}{% + \begin{list}{}{% + \setlength{\leftmargin}{0.5cm}% + }% + \item[]\ignorespaces% +}{% + \unskip% + \end{list}% +} + +% Used when hyperlinks are turned off +\newcommand{\doxyref}[3]{% + \textbf{#1} (\textnormal{#2}\,\pageref{#3})% +} + +% Used for syntax highlighting +\definecolor{comment}{rgb}{0.5,0.0,0.0} +\definecolor{keyword}{rgb}{0.0,0.5,0.0} +\definecolor{keywordtype}{rgb}{0.38,0.25,0.125} +\definecolor{keywordflow}{rgb}{0.88,0.5,0.0} +\definecolor{preprocessor}{rgb}{0.5,0.38,0.125} +\definecolor{stringliteral}{rgb}{0.0,0.125,0.25} +\definecolor{charliteral}{rgb}{0.0,0.5,0.5} +\definecolor{vhdldigit}{rgb}{1.0,0.0,1.0} +\definecolor{vhdlkeyword}{rgb}{0.43,0.0,0.43} +\definecolor{vhdllogic}{rgb}{1.0,0.0,0.0} +\definecolor{vhdlchar}{rgb}{0.0,0.0,0.0} diff --git a/software/firmware/libraries/modbus/documentation/latex/files.tex b/software/firmware/libraries/modbus/documentation/latex/files.tex new file mode 100644 index 0000000..1231238 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/latex/files.tex @@ -0,0 +1,4 @@ +\section{File List} +Here is a list of all files with brief descriptions\-:\begin{DoxyCompactList} +\item\contentsline{section}{\hyperlink{_modbus_rtu_8h}{Modbus\-Rtu.\-h} }{\pageref{_modbus_rtu_8h}}{} +\end{DoxyCompactList} diff --git a/software/firmware/libraries/modbus/documentation/latex/group__buffer.tex b/software/firmware/libraries/modbus/documentation/latex/group__buffer.tex new file mode 100644 index 0000000..5121a77 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/latex/group__buffer.tex @@ -0,0 +1,122 @@ +\hypertarget{group__buffer}{\section{Modbus Buffer Management} +\label{group__buffer}\index{Modbus Buffer Management@{Modbus Buffer Management}} +} +\subsection*{Functions} +\begin{DoxyCompactItemize} +\item +uint16\-\_\-t \hyperlink{group__buffer_ga4fa6ede8df85b7cc70b1282b9547378a}{Modbus\-::get\-In\-Cnt} () +\begin{DoxyCompactList}\small\item\em number of incoming messages \end{DoxyCompactList}\item +uint16\-\_\-t \hyperlink{group__buffer_ga6f831ecaf3678c27dafb663a28bf81f0}{Modbus\-::get\-Out\-Cnt} () +\begin{DoxyCompactList}\small\item\em number of outcoming messages \end{DoxyCompactList}\item +uint16\-\_\-t \hyperlink{group__buffer_ga6883c7f3ff12f084ed56d559d4e06ed0}{Modbus\-::get\-Err\-Cnt} () +\begin{DoxyCompactList}\small\item\em error counter \end{DoxyCompactList}\item +uint8\-\_\-t \hyperlink{group__buffer_ga2f39717d957a929af488c9120488fcdc}{Modbus\-::get\-State} () +\item +uint8\-\_\-t \hyperlink{group__buffer_gace7f726db13adc8feeceab987b719531}{Modbus\-::get\-Last\-Error} () +\begin{DoxyCompactList}\small\item\em get last error message \end{DoxyCompactList}\end{DoxyCompactItemize} + + +\subsection{Detailed Description} + + +\subsection{Function Documentation} +\hypertarget{group__buffer_ga6883c7f3ff12f084ed56d559d4e06ed0}{\index{Modbus Buffer Management@{Modbus Buffer Management}!get\-Err\-Cnt@{get\-Err\-Cnt}} +\index{get\-Err\-Cnt@{get\-Err\-Cnt}!Modbus Buffer Management@{Modbus Buffer Management}} +\subsubsection[{get\-Err\-Cnt}]{\setlength{\rightskip}{0pt plus 5cm}uint16\-\_\-t Modbus\-::get\-Err\-Cnt ( +\begin{DoxyParamCaption} +{} +\end{DoxyParamCaption} +)}}\label{group__buffer_ga6883c7f3ff12f084ed56d559d4e06ed0} + + +error counter + +Get errors counter value This can be useful to diagnose communication. + +\begin{DoxyReturn}{Returns} +errors counter +\end{DoxyReturn} + + +Definition at line 386 of file Modbus\-Rtu.\-h. + +\hypertarget{group__buffer_ga4fa6ede8df85b7cc70b1282b9547378a}{\index{Modbus Buffer Management@{Modbus Buffer Management}!get\-In\-Cnt@{get\-In\-Cnt}} +\index{get\-In\-Cnt@{get\-In\-Cnt}!Modbus Buffer Management@{Modbus Buffer Management}} +\subsubsection[{get\-In\-Cnt}]{\setlength{\rightskip}{0pt plus 5cm}uint16\-\_\-t Modbus\-::get\-In\-Cnt ( +\begin{DoxyParamCaption} +{} +\end{DoxyParamCaption} +)}}\label{group__buffer_ga4fa6ede8df85b7cc70b1282b9547378a} + + +number of incoming messages + +Get input messages counter value This can be useful to diagnose communication. + +\begin{DoxyReturn}{Returns} +input messages counter +\end{DoxyReturn} + + +Definition at line 362 of file Modbus\-Rtu.\-h. + +\hypertarget{group__buffer_gace7f726db13adc8feeceab987b719531}{\index{Modbus Buffer Management@{Modbus Buffer Management}!get\-Last\-Error@{get\-Last\-Error}} +\index{get\-Last\-Error@{get\-Last\-Error}!Modbus Buffer Management@{Modbus Buffer Management}} +\subsubsection[{get\-Last\-Error}]{\setlength{\rightskip}{0pt plus 5cm}uint8\-\_\-t Modbus\-::get\-Last\-Error ( +\begin{DoxyParamCaption} +{} +\end{DoxyParamCaption} +)}}\label{group__buffer_gace7f726db13adc8feeceab987b719531} + + +get last error message + +Get the last error in the protocol processor + +N\-O\-\_\-\-R\-E\-P\-L\-Y = 255 Time-\/out \begin{DoxyReturn}{Returns} +E\-X\-C\-\_\-\-F\-U\-N\-C\-\_\-\-C\-O\-D\-E = 1 Function code not available + +E\-X\-C\-\_\-\-A\-D\-D\-R\-\_\-\-R\-A\-N\-G\-E = 2 Address beyond available space for \hyperlink{class_modbus}{Modbus} registers + +E\-X\-C\-\_\-\-R\-E\-G\-S\-\_\-\-Q\-U\-A\-N\-T = 3 Coils or registers number beyond the available space +\end{DoxyReturn} + + +Definition at line 409 of file Modbus\-Rtu.\-h. + +\hypertarget{group__buffer_ga6f831ecaf3678c27dafb663a28bf81f0}{\index{Modbus Buffer Management@{Modbus Buffer Management}!get\-Out\-Cnt@{get\-Out\-Cnt}} +\index{get\-Out\-Cnt@{get\-Out\-Cnt}!Modbus Buffer Management@{Modbus Buffer Management}} +\subsubsection[{get\-Out\-Cnt}]{\setlength{\rightskip}{0pt plus 5cm}uint16\-\_\-t Modbus\-::get\-Out\-Cnt ( +\begin{DoxyParamCaption} +{} +\end{DoxyParamCaption} +)}}\label{group__buffer_ga6f831ecaf3678c27dafb663a28bf81f0} + + +number of outcoming messages + +Get transmitted messages counter value This can be useful to diagnose communication. + +\begin{DoxyReturn}{Returns} +transmitted messages counter +\end{DoxyReturn} + + +Definition at line 374 of file Modbus\-Rtu.\-h. + +\hypertarget{group__buffer_ga2f39717d957a929af488c9120488fcdc}{\index{Modbus Buffer Management@{Modbus Buffer Management}!get\-State@{get\-State}} +\index{get\-State@{get\-State}!Modbus Buffer Management@{Modbus Buffer Management}} +\subsubsection[{get\-State}]{\setlength{\rightskip}{0pt plus 5cm}uint8\-\_\-t Modbus\-::get\-State ( +\begin{DoxyParamCaption} +{} +\end{DoxyParamCaption} +)}}\label{group__buffer_ga2f39717d957a929af488c9120488fcdc} +Get modbus master state + +\begin{DoxyReturn}{Returns} += 0 I\-D\-L\-E, = 1 W\-A\-I\-T\-I\-N\-G F\-O\-R A\-N\-S\-W\-E\-R +\end{DoxyReturn} + + +Definition at line 396 of file Modbus\-Rtu.\-h. + diff --git a/software/firmware/libraries/modbus/documentation/latex/group__discrete.tex b/software/firmware/libraries/modbus/documentation/latex/group__discrete.tex new file mode 100644 index 0000000..2406e3c --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/latex/group__discrete.tex @@ -0,0 +1,6 @@ +\hypertarget{group__discrete}{\section{Modbus Function Codes for Discrete Coils/\-Inputs} +\label{group__discrete}\index{Modbus Function Codes for Discrete Coils/\-Inputs@{Modbus Function Codes for Discrete Coils/\-Inputs}} +} + + +\subsection{Detailed Description} diff --git a/software/firmware/libraries/modbus/documentation/latex/group__loop.tex b/software/firmware/libraries/modbus/documentation/latex/group__loop.tex new file mode 100644 index 0000000..ead71a6 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/latex/group__loop.tex @@ -0,0 +1,117 @@ +\hypertarget{group__loop}{\section{Modbus Object Management} +\label{group__loop}\index{Modbus Object Management@{Modbus Object Management}} +} +\subsection*{Functions} +\begin{DoxyCompactItemize} +\item +boolean \hyperlink{group__loop_gaf6dd413191ed8a833022046873e0a063}{Modbus\-::get\-Time\-Out\-State} () +\begin{DoxyCompactList}\small\item\em get communication watch-\/dog timer state \end{DoxyCompactList}\item +int8\-\_\-t \hyperlink{group__loop_ga19398cabed57b6d085d014af6c149f54}{Modbus\-::query} (\hyperlink{structmodbus__t}{modbus\-\_\-t} telegram) +\begin{DoxyCompactList}\small\item\em only for master \end{DoxyCompactList}\item +int8\-\_\-t \hyperlink{group__loop_ga53bde78490c1cd8e3c070a676bdcfb0d}{Modbus\-::poll} () +\begin{DoxyCompactList}\small\item\em cyclic poll for master \end{DoxyCompactList}\item +int8\-\_\-t \hyperlink{group__loop_gab3ef20562fc8cee14fc85f7e276890b5}{Modbus\-::poll} (uint16\-\_\-t $\ast$regs, uint8\-\_\-t u8size) +\begin{DoxyCompactList}\small\item\em cyclic poll for slave \end{DoxyCompactList}\end{DoxyCompactItemize} + + +\subsection{Detailed Description} + + +\subsection{Function Documentation} +\hypertarget{group__loop_gaf6dd413191ed8a833022046873e0a063}{\index{Modbus Object Management@{Modbus Object Management}!get\-Time\-Out\-State@{get\-Time\-Out\-State}} +\index{get\-Time\-Out\-State@{get\-Time\-Out\-State}!Modbus Object Management@{Modbus Object Management}} +\subsubsection[{get\-Time\-Out\-State}]{\setlength{\rightskip}{0pt plus 5cm}boolean Modbus\-::get\-Time\-Out\-State ( +\begin{DoxyParamCaption} +{} +\end{DoxyParamCaption} +)}}\label{group__loop_gaf6dd413191ed8a833022046873e0a063} + + +get communication watch-\/dog timer state + +Return communication Watchdog state. It could be usefull to reset outputs if the watchdog is fired. + +\begin{DoxyReturn}{Returns} +T\-R\-U\-E if millis() $>$ u32time\-Out +\end{DoxyReturn} + + +Definition at line 350 of file Modbus\-Rtu.\-h. + +\hypertarget{group__loop_ga53bde78490c1cd8e3c070a676bdcfb0d}{\index{Modbus Object Management@{Modbus Object Management}!poll@{poll}} +\index{poll@{poll}!Modbus Object Management@{Modbus Object Management}} +\subsubsection[{poll}]{\setlength{\rightskip}{0pt plus 5cm}int8\-\_\-t Modbus\-::poll ( +\begin{DoxyParamCaption} +{} +\end{DoxyParamCaption} +)}}\label{group__loop_ga53bde78490c1cd8e3c070a676bdcfb0d} + + +cyclic poll for master + +$\ast$$\ast$$\ast$ Only for \hyperlink{class_modbus}{Modbus} Master $\ast$$\ast$$\ast$ This method checks if there is any incoming answer if pending. If there is no answer, it would change Master state to C\-O\-M\-\_\-\-I\-D\-L\-E. This method must be called only at loop section. Avoid any delay() function. + +Any incoming data would be redirected to au16regs pointer, as defined in its \hyperlink{structmodbus__t}{modbus\-\_\-t} query telegram. + +nothing \begin{DoxyReturn}{Returns} +errors counter +\end{DoxyReturn} + + +Definition at line 513 of file Modbus\-Rtu.\-h. + +\hypertarget{group__loop_gab3ef20562fc8cee14fc85f7e276890b5}{\index{Modbus Object Management@{Modbus Object Management}!poll@{poll}} +\index{poll@{poll}!Modbus Object Management@{Modbus Object Management}} +\subsubsection[{poll}]{\setlength{\rightskip}{0pt plus 5cm}int8\-\_\-t Modbus\-::poll ( +\begin{DoxyParamCaption} +\item[{uint16\-\_\-t $\ast$}]{regs, } +\item[{uint8\-\_\-t}]{u8size} +\end{DoxyParamCaption} +)}}\label{group__loop_gab3ef20562fc8cee14fc85f7e276890b5} + + +cyclic poll for slave + +$\ast$$\ast$$\ast$ Only for \hyperlink{class_modbus}{Modbus} Slave $\ast$$\ast$$\ast$ This method checks if there is any incoming query Afterwards, it would shoot a validation routine plus a register query Avoid any delay() function !!!! After a successful frame between the Master and the Slave, the time-\/out timer is reset. + + +\begin{DoxyParams}{Parameters} +{\em $\ast$regs} & register table for communication exchange \\ +\hline +{\em u8size} & size of the register table \\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +0 if no query, 1..4 if communication error, $>$4 if correct query processed +\end{DoxyReturn} + + +Definition at line 588 of file Modbus\-Rtu.\-h. + +\hypertarget{group__loop_ga19398cabed57b6d085d014af6c149f54}{\index{Modbus Object Management@{Modbus Object Management}!query@{query}} +\index{query@{query}!Modbus Object Management@{Modbus Object Management}} +\subsubsection[{query}]{\setlength{\rightskip}{0pt plus 5cm}int8\-\_\-t Modbus\-::query ( +\begin{DoxyParamCaption} +\item[{{\bf modbus\-\_\-t}}]{telegram} +\end{DoxyParamCaption} +)}}\label{group__loop_ga19398cabed57b6d085d014af6c149f54} + + +only for master + +$\ast$$\ast$$\ast$ Only \hyperlink{class_modbus}{Modbus} Master $\ast$$\ast$$\ast$ Generate a query to an slave with a \hyperlink{structmodbus__t}{modbus\-\_\-t} telegram structure The Master must be in C\-O\-M\-\_\-\-I\-D\-L\-E mode. After it, its state would be C\-O\-M\-\_\-\-W\-A\-I\-T\-I\-N\-G. This method has to be called only in loop() section. + +\begin{DoxySeeAlso}{See Also} +\hyperlink{structmodbus__t}{modbus\-\_\-t} +\end{DoxySeeAlso} + +\begin{DoxyParams}{Parameters} +{\em \hyperlink{structmodbus__t}{modbus\-\_\-t}} & modbus telegram structure (id, fct, ...)\\ +\hline +\end{DoxyParams} +\begin{DoxyRefDesc}{Todo} +\item[\hyperlink{todo__todo000001}{Todo}]finish function 15 \end{DoxyRefDesc} + + +Definition at line 425 of file Modbus\-Rtu.\-h. + diff --git a/software/firmware/libraries/modbus/documentation/latex/group__register.tex b/software/firmware/libraries/modbus/documentation/latex/group__register.tex new file mode 100644 index 0000000..2127655 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/latex/group__register.tex @@ -0,0 +1,6 @@ +\hypertarget{group__register}{\section{Modbus Function Codes for Holding/\-Input Registers} +\label{group__register}\index{Modbus Function Codes for Holding/\-Input Registers@{Modbus Function Codes for Holding/\-Input Registers}} +} + + +\subsection{Detailed Description} diff --git a/software/firmware/libraries/modbus/documentation/latex/group__setup.tex b/software/firmware/libraries/modbus/documentation/latex/group__setup.tex new file mode 100644 index 0000000..4c9fbd4 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/latex/group__setup.tex @@ -0,0 +1,130 @@ +\hypertarget{group__setup}{\section{Modbus Object Instantiation/\-Initialization} +\label{group__setup}\index{Modbus Object Instantiation/\-Initialization@{Modbus Object Instantiation/\-Initialization}} +} +\subsection*{Functions} +\begin{DoxyCompactItemize} +\item +\hyperlink{group__setup_ga101809cdd4734537bab58dc315a840b4}{Modbus\-::\-Modbus} () +\begin{DoxyCompactList}\small\item\em Default Constructor for Master through Serial. \end{DoxyCompactList}\item +void \hyperlink{group__setup_ga475a4fa0fac491307b10c4529ad6d2a0}{Modbus\-::begin} (long u32speed) +\begin{DoxyCompactList}\small\item\em Initialize class object. \end{DoxyCompactList}\item +void \hyperlink{group__setup_ga9bd497e97ac1777d4f0d4171078d60e0}{Modbus\-::set\-I\-D} (uint8\-\_\-t u8id) +\begin{DoxyCompactList}\small\item\em write new I\-D for the slave \end{DoxyCompactList}\item +uint8\-\_\-t \hyperlink{group__setup_ga6449894306ff8cc5d4caff09b1b0d1ce}{Modbus\-::get\-I\-D} () +\begin{DoxyCompactList}\small\item\em get slave I\-D between 1 and 247 \end{DoxyCompactList}\item +void \hyperlink{group__setup_gaf828190ebe24efb1b3b1957429f3872e}{Modbus\-::set\-Time\-Out} (uint16\-\_\-t u16timeout) +\begin{DoxyCompactList}\small\item\em write communication watch-\/dog timer \end{DoxyCompactList}\end{DoxyCompactItemize} + + +\subsection{Detailed Description} + + +\subsection{Function Documentation} +\hypertarget{group__setup_ga475a4fa0fac491307b10c4529ad6d2a0}{\index{Modbus Object Instantiation/\-Initialization@{Modbus Object Instantiation/\-Initialization}!begin@{begin}} +\index{begin@{begin}!Modbus Object Instantiation/Initialization@{Modbus Object Instantiation/\-Initialization}} +\subsubsection[{begin}]{\setlength{\rightskip}{0pt plus 5cm}void Modbus\-::begin ( +\begin{DoxyParamCaption} +\item[{long}]{u32speed} +\end{DoxyParamCaption} +)}}\label{group__setup_ga475a4fa0fac491307b10c4529ad6d2a0} + + +Initialize class object. + +Sets up the serial port using specified baud rate. Call once class has been instantiated, typically within setup(). + +\begin{DoxySeeAlso}{See Also} +\href{http://arduino.cc/en/Serial/Begin#.Uy4CJ6aKlHY}{\tt http\-://arduino.\-cc/en/\-Serial/\-Begin\#.\-Uy4\-C\-J6a\-Kl\-H\-Y} +\end{DoxySeeAlso} + +\begin{DoxyParams}{Parameters} +{\em speed} & baud rate, in standard increments (300..115200) \\ +\hline +{\em config} & data frame settings (data length, parity and stop bits) \\ +\hline +\end{DoxyParams} + + +Definition at line 250 of file Modbus\-Rtu.\-h. + +\hypertarget{group__setup_ga6449894306ff8cc5d4caff09b1b0d1ce}{\index{Modbus Object Instantiation/\-Initialization@{Modbus Object Instantiation/\-Initialization}!get\-I\-D@{get\-I\-D}} +\index{get\-I\-D@{get\-I\-D}!Modbus Object Instantiation/Initialization@{Modbus Object Instantiation/\-Initialization}} +\subsubsection[{get\-I\-D}]{\setlength{\rightskip}{0pt plus 5cm}uint8\-\_\-t Modbus\-::get\-I\-D ( +\begin{DoxyParamCaption} +{} +\end{DoxyParamCaption} +)}}\label{group__setup_ga6449894306ff8cc5d4caff09b1b0d1ce} + + +get slave I\-D between 1 and 247 + +Method to read current slave I\-D address. + +\begin{DoxyReturn}{Returns} +u8id current slave address between 1 and 247 +\end{DoxyReturn} + + +Definition at line 323 of file Modbus\-Rtu.\-h. + +\hypertarget{group__setup_ga101809cdd4734537bab58dc315a840b4}{\index{Modbus Object Instantiation/\-Initialization@{Modbus Object Instantiation/\-Initialization}!Modbus@{Modbus}} +\index{Modbus@{Modbus}!Modbus Object Instantiation/Initialization@{Modbus Object Instantiation/\-Initialization}} +\subsubsection[{Modbus}]{\setlength{\rightskip}{0pt plus 5cm}Modbus\-::\-Modbus ( +\begin{DoxyParamCaption} +{} +\end{DoxyParamCaption} +)}}\label{group__setup_ga101809cdd4734537bab58dc315a840b4} + + +Default Constructor for Master through Serial. + + + +Definition at line 204 of file Modbus\-Rtu.\-h. + +\hypertarget{group__setup_ga9bd497e97ac1777d4f0d4171078d60e0}{\index{Modbus Object Instantiation/\-Initialization@{Modbus Object Instantiation/\-Initialization}!set\-I\-D@{set\-I\-D}} +\index{set\-I\-D@{set\-I\-D}!Modbus Object Instantiation/Initialization@{Modbus Object Instantiation/\-Initialization}} +\subsubsection[{set\-I\-D}]{\setlength{\rightskip}{0pt plus 5cm}void Modbus\-::set\-I\-D ( +\begin{DoxyParamCaption} +\item[{uint8\-\_\-t}]{u8id} +\end{DoxyParamCaption} +)}}\label{group__setup_ga9bd497e97ac1777d4f0d4171078d60e0} + + +write new I\-D for the slave + +Method to write a new slave I\-D address. + + +\begin{DoxyParams}{Parameters} +{\em u8id} & new slave address between 1 and 247 \\ +\hline +\end{DoxyParams} + + +Definition at line 310 of file Modbus\-Rtu.\-h. + +\hypertarget{group__setup_gaf828190ebe24efb1b3b1957429f3872e}{\index{Modbus Object Instantiation/\-Initialization@{Modbus Object Instantiation/\-Initialization}!set\-Time\-Out@{set\-Time\-Out}} +\index{set\-Time\-Out@{set\-Time\-Out}!Modbus Object Instantiation/Initialization@{Modbus Object Instantiation/\-Initialization}} +\subsubsection[{set\-Time\-Out}]{\setlength{\rightskip}{0pt plus 5cm}void Modbus\-::set\-Time\-Out ( +\begin{DoxyParamCaption} +\item[{uint16\-\_\-t}]{u16time\-Out} +\end{DoxyParamCaption} +)}}\label{group__setup_gaf828190ebe24efb1b3b1957429f3872e} + + +write communication watch-\/dog timer + +Initialize time-\/out parameter. + +Call once class has been instantiated, typically within setup(). The time-\/out timer is reset each time that there is a successful communication between Master and Slave. It works for both. + + +\begin{DoxyParams}{Parameters} +{\em time-\/out} & value (ms) \\ +\hline +\end{DoxyParams} + + +Definition at line 338 of file Modbus\-Rtu.\-h. + diff --git a/software/firmware/libraries/modbus/documentation/latex/modules.tex b/software/firmware/libraries/modbus/documentation/latex/modules.tex new file mode 100644 index 0000000..00365d6 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/latex/modules.tex @@ -0,0 +1,8 @@ +\section{Modules} +Here is a list of all modules\-:\begin{DoxyCompactList} +\item \contentsline{section}{Modbus Object Instantiation/\-Initialization}{\pageref{group__setup}}{} +\item \contentsline{section}{Modbus Object Management}{\pageref{group__loop}}{} +\item \contentsline{section}{Modbus Buffer Management}{\pageref{group__buffer}}{} +\item \contentsline{section}{Modbus Function Codes for Discrete Coils/\-Inputs}{\pageref{group__discrete}}{} +\item \contentsline{section}{Modbus Function Codes for Holding/\-Input Registers}{\pageref{group__register}}{} +\end{DoxyCompactList} diff --git a/software/firmware/libraries/modbus/documentation/latex/refman.tex b/software/firmware/libraries/modbus/documentation/latex/refman.tex new file mode 100644 index 0000000..6845e48 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/latex/refman.tex @@ -0,0 +1,162 @@ +\documentclass[twoside]{book} + +% Packages required by doxygen +\usepackage{calc} +\usepackage{doxygen} +\usepackage{graphicx} +\usepackage[utf8]{inputenc} +\usepackage{makeidx} +\usepackage{multicol} +\usepackage{multirow} +\usepackage{textcomp} +\usepackage[table]{xcolor} + +% Font selection +\usepackage[T1]{fontenc} +\usepackage{mathptmx} +\usepackage[scaled=.90]{helvet} +\usepackage{courier} +\usepackage{amssymb} +\usepackage{sectsty} +\renewcommand{\familydefault}{\sfdefault} +\allsectionsfont{% + \fontseries{bc}\selectfont% + \color{darkgray}% +} +\renewcommand{\DoxyLabelFont}{% + \fontseries{bc}\selectfont% + \color{darkgray}% +} + +% Page & text layout +\usepackage{geometry} +\geometry{% + a4paper,% + top=2.5cm,% + bottom=2.5cm,% + left=2.5cm,% + right=2.5cm% +} +\tolerance=750 +\hfuzz=15pt +\hbadness=750 +\setlength{\emergencystretch}{15pt} +\setlength{\parindent}{0cm} +\setlength{\parskip}{0.2cm} +\makeatletter +\renewcommand{\paragraph}{% + \@startsection{paragraph}{4}{0ex}{-1.0ex}{1.0ex}{% + \normalfont\normalsize\bfseries\SS@parafont% + }% +} +\renewcommand{\subparagraph}{% + \@startsection{subparagraph}{5}{0ex}{-1.0ex}{1.0ex}{% + \normalfont\normalsize\bfseries\SS@subparafont% + }% +} +\makeatother + +% Headers & footers +\usepackage{fancyhdr} +\pagestyle{fancyplain} +\fancyhead[LE]{\fancyplain{}{\bfseries\thepage}} +\fancyhead[CE]{\fancyplain{}{}} +\fancyhead[RE]{\fancyplain{}{\bfseries\leftmark}} +\fancyhead[LO]{\fancyplain{}{\bfseries\rightmark}} +\fancyhead[CO]{\fancyplain{}{}} +\fancyhead[RO]{\fancyplain{}{\bfseries\thepage}} +\fancyfoot[LE]{\fancyplain{}{}} +\fancyfoot[CE]{\fancyplain{}{}} +\fancyfoot[RE]{\fancyplain{}{\bfseries\scriptsize Generated on Tue Sep 9 2014 21:52:15 for Modbus Master and Slave for Arduino by Doxygen }} +\fancyfoot[LO]{\fancyplain{}{\bfseries\scriptsize Generated on Tue Sep 9 2014 21:52:15 for Modbus Master and Slave for Arduino by Doxygen }} +\fancyfoot[CO]{\fancyplain{}{}} +\fancyfoot[RO]{\fancyplain{}{}} +\renewcommand{\footrulewidth}{0.4pt} +\renewcommand{\chaptermark}[1]{% + \markboth{#1}{}% +} +\renewcommand{\sectionmark}[1]{% + \markright{\thesection\ #1}% +} + +% Indices & bibliography +\usepackage{natbib} +\usepackage[titles]{tocloft} +\setcounter{tocdepth}{3} +\setcounter{secnumdepth}{5} +\makeindex + +% Hyperlinks (required, but should be loaded last) +\usepackage{ifpdf} +\ifpdf + \usepackage[pdftex,pagebackref=true]{hyperref} +\else + \usepackage[ps2pdf,pagebackref=true]{hyperref} +\fi +\hypersetup{% + colorlinks=true,% + linkcolor=blue,% + citecolor=blue,% + unicode% +} + +% Custom commands +\newcommand{\clearemptydoublepage}{% + \newpage{\pagestyle{empty}\cleardoublepage}% +} + + +%===== C O N T E N T S ===== + +\begin{document} + +% Titlepage & ToC +\hypersetup{pageanchor=false} +\pagenumbering{roman} +\begin{titlepage} +\vspace*{7cm} +\begin{center}% +{\Large Modbus Master and Slave for Arduino \\[1ex]\large 1.\-2 }\\ +\vspace*{1cm} +{\large Generated by Doxygen 1.8.4}\\ +\vspace*{0.5cm} +{\small Tue Sep 9 2014 21:52:15}\\ +\end{center} +\end{titlepage} +\clearemptydoublepage +\tableofcontents +\clearemptydoublepage +\pagenumbering{arabic} +\hypersetup{pageanchor=true} + +%--- Begin generated contents --- +\chapter{Todo List} +\label{todo} +\hypertarget{todo}{} +\input{todo} +\chapter{Module Index} +\input{modules} +\chapter{Class Index} +\input{annotated} +\chapter{File Index} +\input{files} +\chapter{Module Documentation} +\input{group__setup} +\include{group__loop} +\include{group__buffer} +\include{group__discrete} +\include{group__register} +\chapter{Class Documentation} +\input{class_modbus} +\input{structmodbus__t} +\chapter{File Documentation} +\input{_modbus_rtu_8h} +%--- End generated contents --- + +% Index +\newpage +\phantomsection +\addcontentsline{toc}{part}{Index} +\printindex + +\end{document} diff --git a/software/firmware/libraries/modbus/documentation/latex/structmodbus__t.tex b/software/firmware/libraries/modbus/documentation/latex/structmodbus__t.tex new file mode 100644 index 0000000..17ed743 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/latex/structmodbus__t.tex @@ -0,0 +1,75 @@ +\hypertarget{structmodbus__t}{\section{modbus\-\_\-t Struct Reference} +\label{structmodbus__t}\index{modbus\-\_\-t@{modbus\-\_\-t}} +} + + +Master query structure\-: This includes all the necessary fields to make the Master generate a \hyperlink{class_modbus}{Modbus} query. A Master may keep several of these structures and send them cyclically or use them according to program needs. + + + + +{\ttfamily \#include $<$Modbus\-Rtu.\-h$>$} + +\subsection*{Public Attributes} +\begin{DoxyCompactItemize} +\item +uint8\-\_\-t \hyperlink{structmodbus__t_af78ad11f93e63022a1c279de7206358c}{u8id} +\item +uint8\-\_\-t \hyperlink{structmodbus__t_a57d1630d4548e5d50d79e206a48b09bc}{u8fct} +\item +uint16\-\_\-t \hyperlink{structmodbus__t_a224ead9ff72467696e94fba9cf06bd3c}{u16\-Reg\-Add} +\item +uint16\-\_\-t \hyperlink{structmodbus__t_a5b9cee9c1a9415d927543f6cf054eb43}{u16\-Coils\-No} +\item +uint16\-\_\-t $\ast$ \hyperlink{structmodbus__t_a36212dd6316cbffb8ea31b2a2f5ae1be}{au16reg} +\end{DoxyCompactItemize} + + +\subsection{Detailed Description} +Master query structure\-: This includes all the necessary fields to make the Master generate a \hyperlink{class_modbus}{Modbus} query. A Master may keep several of these structures and send them cyclically or use them according to program needs. + +Definition at line 48 of file Modbus\-Rtu.\-h. + + + +\subsection{Member Data Documentation} +\hypertarget{structmodbus__t_a36212dd6316cbffb8ea31b2a2f5ae1be}{\index{modbus\-\_\-t@{modbus\-\_\-t}!au16reg@{au16reg}} +\index{au16reg@{au16reg}!modbus_t@{modbus\-\_\-t}} +\subsubsection[{au16reg}]{\setlength{\rightskip}{0pt plus 5cm}uint16\-\_\-t$\ast$ modbus\-\_\-t\-::au16reg}}\label{structmodbus__t_a36212dd6316cbffb8ea31b2a2f5ae1be} +Pointer to memory image in master + +Definition at line 53 of file Modbus\-Rtu.\-h. + +\hypertarget{structmodbus__t_a5b9cee9c1a9415d927543f6cf054eb43}{\index{modbus\-\_\-t@{modbus\-\_\-t}!u16\-Coils\-No@{u16\-Coils\-No}} +\index{u16\-Coils\-No@{u16\-Coils\-No}!modbus_t@{modbus\-\_\-t}} +\subsubsection[{u16\-Coils\-No}]{\setlength{\rightskip}{0pt plus 5cm}uint16\-\_\-t modbus\-\_\-t\-::u16\-Coils\-No}}\label{structmodbus__t_a5b9cee9c1a9415d927543f6cf054eb43} +Number of coils or registers to access + +Definition at line 52 of file Modbus\-Rtu.\-h. + +\hypertarget{structmodbus__t_a224ead9ff72467696e94fba9cf06bd3c}{\index{modbus\-\_\-t@{modbus\-\_\-t}!u16\-Reg\-Add@{u16\-Reg\-Add}} +\index{u16\-Reg\-Add@{u16\-Reg\-Add}!modbus_t@{modbus\-\_\-t}} +\subsubsection[{u16\-Reg\-Add}]{\setlength{\rightskip}{0pt plus 5cm}uint16\-\_\-t modbus\-\_\-t\-::u16\-Reg\-Add}}\label{structmodbus__t_a224ead9ff72467696e94fba9cf06bd3c} +Address of the first register to access at slave/s + +Definition at line 51 of file Modbus\-Rtu.\-h. + +\hypertarget{structmodbus__t_a57d1630d4548e5d50d79e206a48b09bc}{\index{modbus\-\_\-t@{modbus\-\_\-t}!u8fct@{u8fct}} +\index{u8fct@{u8fct}!modbus_t@{modbus\-\_\-t}} +\subsubsection[{u8fct}]{\setlength{\rightskip}{0pt plus 5cm}uint8\-\_\-t modbus\-\_\-t\-::u8fct}}\label{structmodbus__t_a57d1630d4548e5d50d79e206a48b09bc} +Function code\-: 1, 2, 3, 4, 5, 6, 15 or 16 + +Definition at line 50 of file Modbus\-Rtu.\-h. + +\hypertarget{structmodbus__t_af78ad11f93e63022a1c279de7206358c}{\index{modbus\-\_\-t@{modbus\-\_\-t}!u8id@{u8id}} +\index{u8id@{u8id}!modbus_t@{modbus\-\_\-t}} +\subsubsection[{u8id}]{\setlength{\rightskip}{0pt plus 5cm}uint8\-\_\-t modbus\-\_\-t\-::u8id}}\label{structmodbus__t_af78ad11f93e63022a1c279de7206358c} +Slave address between 1 and 247. 0 means broadcast + +Definition at line 49 of file Modbus\-Rtu.\-h. + + + +The documentation for this struct was generated from the following file\-:\begin{DoxyCompactItemize} +\item +\hyperlink{_modbus_rtu_8h}{Modbus\-Rtu.\-h}\end{DoxyCompactItemize} diff --git a/software/firmware/libraries/modbus/documentation/latex/todo.tex b/software/firmware/libraries/modbus/documentation/latex/todo.tex new file mode 100644 index 0000000..f715559 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/latex/todo.tex @@ -0,0 +1,6 @@ + +\begin{DoxyRefList} +\item[\label{todo__todo000001}% +\hypertarget{todo__todo000001}{}% +Member \hyperlink{group__loop_ga19398cabed57b6d085d014af6c149f54}{Modbus\-:\-:query} (\hyperlink{structmodbus__t}{modbus\-\_\-t} telegram)]finish function 15 +\end{DoxyRefList} \ No newline at end of file diff --git a/software/firmware/libraries/modbus/documentation/rtf/refman.rtf b/software/firmware/libraries/modbus/documentation/rtf/refman.rtf new file mode 100644 index 0000000..105c995 --- /dev/null +++ b/software/firmware/libraries/modbus/documentation/rtf/refman.rtf @@ -0,0 +1,1546 @@ +{\rtf1\ansi\ansicpg1252\uc1 \deff0\deflang1033\deflangfe1033 +{\fonttbl {\f0\froman\fcharset0\fprq2{\*\panose 02020603050405020304}Times New Roman;} +{\f1\fswiss\fcharset0\fprq2{\*\panose 020b0604020202020204}Arial;} +{\f2\fmodern\fcharset0\fprq1{\*\panose 02070309020205020404}Courier New;} +{\f3\froman\fcharset2\fprq2{\*\panose 05050102010706020507}Symbol;} +} +{\colortbl;\red0\green0\blue0;\red0\green0\blue255;\red0\green255\blue255;\red0\green255\blue0;\red255\green0\blue255;\red255\green0\blue0;\red255\green255\blue0;\red255\green255\blue255;\red0\green0\blue128;\red0\green128\blue128;\red0\green128\blue0;\red128\green0\blue128;\red128\green0\blue0;\red128\green128\blue0;\red128\green128\blue128;\red192\green192\blue192;} +{\stylesheet +{\widctlpar\adjustright \fs20\cgrid \snext0 Normal;} +{\s1\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs36\kerning36\cgrid \sbasedon0 \snext0 heading 1;} +{\s2\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs28\kerning28\cgrid \sbasedon0 \snext0 heading 2;} +{\s3\sb240\sa60\keepn\widctlpar\adjustright \b\f1\cgrid \sbasedon0 \snext0 heading 3;} +{\s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid \sbasedon0 \snext0 heading 4;}{\*\cs10 \additive Default Paragraph Font;} +{\s5\sb90\sa30\keepn\widctlpar\adjustright \b\f1\fs20\cgrid \sbasedon0 \snext0 heading 5;}{\*\cs10 \additive Default Paragraph Font;} +{\s15\qc\sb240\sa60\widctlpar\outlinelevel0\adjustright \b\f1\fs32\kerning28\cgrid \sbasedon0 \snext15 Title;} +{\s16\qc\sa60\widctlpar\outlinelevel1\adjustright \f1\cgrid \sbasedon0 \snext16 Subtitle;} +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid \sbasedon0 \snext17 BodyText;} +{\s18\widctlpar\fs22\cgrid \sbasedon0 \snext18 DenseText;} +{\s28\widctlpar\tqc\tx4320\tqr\tx8640\adjustright \fs20\cgrid \sbasedon0 \snext28 header;} +{\s29\widctlpar\tqc\tx4320\tqr\tx8640\qr\adjustright \fs20\cgrid \sbasedon0 \snext29 footer;} +{\s30\li360\sa60\sb120\keepn\widctlpar\adjustright \b\f1\fs20\cgrid \sbasedon0 \snext30 GroupHeader;} +{\s40\li0\widctlpar\adjustright \shading1000\cbpat8 \f2\fs16\cgrid \sbasedon0 \snext41 Code Example 0;} +{\s41\li360\widctlpar\adjustright \shading1000\cbpat8 \f2\fs16\cgrid \sbasedon0 \snext42 Code Example 1;} +{\s42\li720\widctlpar\adjustright \shading1000\cbpat8 \f2\fs16\cgrid \sbasedon0 \snext43 Code Example 2;} +{\s43\li1080\widctlpar\adjustright \shading1000\cbpat8 \f2\fs16\cgrid \sbasedon0 \snext44 Code Example 3;} +{\s44\li1440\widctlpar\adjustright \shading1000\cbpat8 \f2\fs16\cgrid \sbasedon0 \snext45 Code Example 4;} +{\s45\li1800\widctlpar\adjustright \shading1000\cbpat8 \f2\fs16\cgrid \sbasedon0 \snext46 Code Example 5;} +{\s46\li2160\widctlpar\adjustright \shading1000\cbpat8 \f2\fs16\cgrid \sbasedon0 \snext47 Code Example 6;} +{\s47\li2520\widctlpar\adjustright \shading1000\cbpat8 \f2\fs16\cgrid \sbasedon0 \snext48 Code Example 7;} +{\s48\li2880\widctlpar\adjustright \shading1000\cbpat8 \f2\fs16\cgrid \sbasedon0 \snext49 Code Example 8;} +{\s49\li3240\widctlpar\adjustright \shading1000\cbpat8 \f2\fs16\cgrid \sbasedon0 \snext49 Code Example 9;} +{\s50\li0\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid \sbasedon0 \snext51 List Continue 0;} +{\s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid \sbasedon0 \snext52 List Continue 1;} +{\s52\li720\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid \sbasedon0 \snext53 List Continue 2;} +{\s53\li1080\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid \sbasedon0 \snext54 List Continue 3;} +{\s54\li1440\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid \sbasedon0 \snext55 List Continue 4;} +{\s55\li1800\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid \sbasedon0 \snext56 List Continue 5;} +{\s56\li2160\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid \sbasedon0 \snext57 List Continue 6;} +{\s57\li2520\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid \sbasedon0 \snext58 List Continue 7;} +{\s58\li2880\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid \sbasedon0 \snext59 List Continue 8;} +{\s59\li3240\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid \sbasedon0 \snext59 List Continue 9;} +{\s60\li0\widctlpar\ql\adjustright \fs20\cgrid \sbasedon0 \snext61 DescContinue 0;} +{\s61\li360\widctlpar\ql\adjustright \fs20\cgrid \sbasedon0 \snext62 DescContinue 1;} +{\s62\li720\widctlpar\ql\adjustright \fs20\cgrid \sbasedon0 \snext63 DescContinue 2;} +{\s63\li1080\widctlpar\ql\adjustright \fs20\cgrid \sbasedon0 \snext64 DescContinue 3;} +{\s64\li1440\widctlpar\ql\adjustright \fs20\cgrid \sbasedon0 \snext65 DescContinue 4;} +{\s65\li1800\widctlpar\ql\adjustright \fs20\cgrid \sbasedon0 \snext66 DescContinue 5;} +{\s66\li2160\widctlpar\ql\adjustright \fs20\cgrid \sbasedon0 \snext67 DescContinue 6;} +{\s67\li2520\widctlpar\ql\adjustright \fs20\cgrid \sbasedon0 \snext68 DescContinue 7;} +{\s68\li2880\widctlpar\ql\adjustright \fs20\cgrid \sbasedon0 \snext69 DescContinue 8;} +{\s69\li3240\widctlpar\ql\adjustright \fs20\cgrid \sbasedon0 \snext69 DescContinue 9;} +{\s70\li0\sa30\sb30\widctlpar\tqr\tldot\tx8640\adjustright \fs20\cgrid \sbasedon0 \snext81 LatexTOC 0;} +{\s71\li360\sa27\sb27\widctlpar\tqr\tldot\tx8640\adjustright \fs20\cgrid \sbasedon0 \snext82 LatexTOC 1;} +{\s72\li720\sa24\sb24\widctlpar\tqr\tldot\tx8640\adjustright \fs20\cgrid \sbasedon0 \snext83 LatexTOC 2;} +{\s73\li1080\sa21\sb21\widctlpar\tqr\tldot\tx8640\adjustright \fs20\cgrid \sbasedon0 \snext84 LatexTOC 3;} +{\s74\li1440\sa18\sb18\widctlpar\tqr\tldot\tx8640\adjustright \fs20\cgrid \sbasedon0 \snext85 LatexTOC 4;} +{\s75\li1800\sa15\sb15\widctlpar\tqr\tldot\tx8640\adjustright \fs20\cgrid \sbasedon0 \snext86 LatexTOC 5;} +{\s76\li2160\sa12\sb12\widctlpar\tqr\tldot\tx8640\adjustright \fs20\cgrid \sbasedon0 \snext87 LatexTOC 6;} +{\s77\li2520\sa9\sb9\widctlpar\tqr\tldot\tx8640\adjustright \fs20\cgrid \sbasedon0 \snext88 LatexTOC 7;} +{\s78\li2880\sa6\sb6\widctlpar\tqr\tldot\tx8640\adjustright \fs20\cgrid \sbasedon0 \snext89 LatexTOC 8;} +{\s79\li3240\sa3\sb3\widctlpar\tqr\tldot\tx8640\adjustright \fs20\cgrid \sbasedon0 \snext89 LatexTOC 9;} +{\s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid \sbasedon0 \snext81 \sautoupd List Bullet 0;} +{\s81\fi-360\li720\widctlpar\jclisttab\tx720{\*\pn \pnlvlbody\ilvl0\ls2\pnrnot0\pndec }\ls2\adjustright \fs20\cgrid \sbasedon0 \snext82 \sautoupd List Bullet 1;} +{\s82\fi-360\li1080\widctlpar\jclisttab\tx1080{\*\pn \pnlvlbody\ilvl0\ls3\pnrnot0\pndec }\ls3\adjustright \fs20\cgrid \sbasedon0 \snext83 \sautoupd List Bullet 2;} +{\s83\fi-360\li1440\widctlpar\jclisttab\tx1440{\*\pn \pnlvlbody\ilvl0\ls4\pnrnot0\pndec }\ls4\adjustright \fs20\cgrid \sbasedon0 \snext84 \sautoupd List Bullet 3;} +{\s84\fi-360\li1800\widctlpar\jclisttab\tx1800{\*\pn \pnlvlbody\ilvl0\ls5\pnrnot0\pndec }\ls5\adjustright \fs20\cgrid \sbasedon0 \snext85 \sautoupd List Bullet 4;} +{\s85\fi-360\li2160\widctlpar\jclisttab\tx2160{\*\pn \pnlvlbody\ilvl0\ls6\pnrnot0\pndec }\ls6\adjustright \fs20\cgrid \sbasedon0 \snext86 \sautoupd List Bullet 5;} +{\s86\fi-360\li2520\widctlpar\jclisttab\tx2520{\*\pn \pnlvlbody\ilvl0\ls7\pnrnot0\pndec }\ls7\adjustright \fs20\cgrid \sbasedon0 \snext87 \sautoupd List Bullet 6;} +{\s87\fi-360\li2880\widctlpar\jclisttab\tx2880{\*\pn \pnlvlbody\ilvl0\ls8\pnrnot0\pndec }\ls8\adjustright \fs20\cgrid \sbasedon0 \snext88 \sautoupd List Bullet 7;} +{\s88\fi-360\li3240\widctlpar\jclisttab\tx3240{\*\pn \pnlvlbody\ilvl0\ls9\pnrnot0\pndec }\ls9\adjustright \fs20\cgrid \sbasedon0 \snext89 \sautoupd List Bullet 8;} +{\s89\fi-360\li3600\widctlpar\jclisttab\tx3600{\*\pn \pnlvlbody\ilvl0\ls10\pnrnot0\pndec }\ls10\adjustright \fs20\cgrid \sbasedon0 \snext89 \sautoupd List Bullet 9;} +{\s90\fi-360\li360\widctlpar\fs20\cgrid \sbasedon0 \snext91 \sautoupd List Enum 0;} +{\s91\fi-360\li720\widctlpar\fs20\cgrid \sbasedon0 \snext92 \sautoupd List Enum 1;} +{\s92\fi-360\li1080\widctlpar\fs20\cgrid \sbasedon0 \snext93 \sautoupd List Enum 2;} +{\s93\fi-360\li1440\widctlpar\fs20\cgrid \sbasedon0 \snext94 \sautoupd List Enum 3;} +{\s94\fi-360\li1800\widctlpar\fs20\cgrid \sbasedon0 \snext95 \sautoupd List Enum 4;} +{\s95\fi-360\li2160\widctlpar\fs20\cgrid \sbasedon0 \snext96 \sautoupd List Enum 5;} +{\s96\fi-360\li2520\widctlpar\fs20\cgrid \sbasedon0 \snext96 \sautoupd List Enum 5;} +{\s97\fi-360\li2880\widctlpar\fs20\cgrid \sbasedon0 \snext98 \sautoupd List Enum 7;} +{\s98\fi-360\li3240\widctlpar\fs20\cgrid \sbasedon0 \snext99 \sautoupd List Enum 8;} +{\s99\fi-360\li3600\widctlpar\fs20\cgrid \sbasedon0 \snext99 \sautoupd List Enum 9;} +} +{\comment begin body} +{\info +{\title {\comment Modbus Master and Slave for Arduino {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +1.2 \par +}}Modbus Master and Slave for Arduino} +{\comment Generated byDoxgyen. } +{\creatim \yr2014\mo9\dy9\hr21\min52\sec15} +}\pard\plain +\sectd\pgnlcrm +{\footer \s29\widctlpar\tqc\tx4320\tqr\tx8640\qr\adjustright \fs20\cgrid {\chpgn}} +\pard\plain \s16\qc\sa60\widctlpar\outlinelevel1\adjustright \f1\cgrid +\vertalc\qc\par\par\par\par\par\par\par +\pard\plain \s15\qc\sb240\sa60\widctlpar\outlinelevel0\adjustright \b\f1\fs32\kerning28\cgrid +{\field\fldedit {\*\fldinst TITLE \\*MERGEFORMAT}{\fldrslt TITLE}}\par +\pard\plain \s16\qc\sa60\widctlpar\outlinelevel1\adjustright \f1\cgrid +\par +\par\par\par\par\par\par\par\par\par\par\par\par +\pard\plain \s16\qc\sa60\widctlpar\outlinelevel1\adjustright \f1\cgrid +{\field\fldedit {\*\fldinst AUTHOR \\*MERGEFORMAT}{\fldrslt AUTHOR}}\par +Version 1.2\par{\field\fldedit {\*\fldinst CREATEDATE \\*MERGEFORMAT}{\fldrslt CREATEDATE}}\par +\page\page\vertalt +\pard\plain +\s1\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs36\kerning36\cgrid Table of Contents\par +\pard\plain \par +{\field\fldedit {\*\fldinst TOC \\f \\*MERGEFORMAT}{\fldrslt Table of contents}}\par +\pard\plain +\sect \sbkpage \pgndec \pgnrestart +\sect \sectd \sbknone +{\footer \s29\widctlpar\tqc\tx4320\tqr\tx8640\qr\adjustright \fs20\cgrid {\chpgn}} + +\pard\plain \sect\sbkpage +\s1\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs36\kerning36\cgrid +Todo List{\tc \v Todo List}\par \pard\plain +{\bkmkstart AAAAAAAACV} +{\bkmkend AAAAAAAACV} +\par \pard\plain +{ +\pard\plain \s17\sa60\sb30\widctlpar\qj \fs22\cgrid {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +{\s5\sb90\sa30\keepn\widctlpar\adjustright \b\f1\fs20\cgrid +{\bkmkstart AAAAAAAABP} +{\bkmkend AAAAAAAABP} +Member {\b Modbus::query} ({\b modbus_t} telegram)\par +} +{\pard\plain \s61\li360\widctlpar\ql\adjustright \fs20\cgrid finish function 15 \par} +}} + +\pard\plain \sect\sbkpage +\s1\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs36\kerning36\cgrid +Module Index\par \pard\plain +{\tc \v Module Index} +\pard\plain \s2\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs28\kerning28\cgrid +Modules\par \pard\plain +{ +\pard\plain \s17\sa60\sb30\widctlpar\qj \fs22\cgrid Here is a list of all modules:} +{ +\par +\pard\plain \s71\li360\sa27\sb27\widctlpar\tqr\tldot\tx8640\adjustright \fs20\cgrid +Modbus Object Instantiation/Initialization\tab {\field\fldedit {\*\fldinst PAGEREF AAAAAAAABQ \\*MERGEFORMAT}{\fldrslt pagenum}} +\par +Modbus Object Management\tab {\field\fldedit {\*\fldinst PAGEREF AAAAAAAABW \\*MERGEFORMAT}{\fldrslt pagenum}} +\par +Modbus Buffer Management\tab {\field\fldedit {\*\fldinst PAGEREF AAAAAAAACB \\*MERGEFORMAT}{\fldrslt pagenum}} +\par +Modbus Function Codes for Discrete Coils/Inputs\tab {\field\fldedit {\*\fldinst PAGEREF AAAAAAAACH \\*MERGEFORMAT}{\fldrslt pagenum}} +\par +Modbus Function Codes for Holding/Input Registers\tab {\field\fldedit {\*\fldinst PAGEREF AAAAAAAACI \\*MERGEFORMAT}{\fldrslt pagenum}} +\par +} +\pard\plain \sect\sbkpage +\s1\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs36\kerning36\cgrid +Class Index\par \pard\plain +{\tc \v Class Index} +\pard\plain \s2\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs28\kerning28\cgrid +Class List\par \pard\plain +{ +\pard\plain \s17\sa60\sb30\widctlpar\qj \fs22\cgrid Here are the classes, structs, unions and interfaces with brief descriptions:} +{ +\par +\pard\plain \s71\li360\sa27\sb27\widctlpar\tqr\tldot\tx8640\adjustright \fs20\cgrid +{\b {\b Modbus} ({\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Arduino class library for communicating with {\b Modbus} devices over USB/RS232/485 (via RTU protocol) })} \tab {\field\fldedit {\*\fldinst PAGEREF AAAAAAAACJ \\*MERGEFORMAT}{\fldrslt pagenum}} +\par +{\b {\b modbus_t} ({\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Master query structure: This includes all the necessary fields to make the Master generate a {\b Modbus} query. A Master may keep several of these structures and send them cyclically or use them according to program needs })} \tab {\field\fldedit {\*\fldinst PAGEREF AAAAAAAACP \\*MERGEFORMAT}{\fldrslt pagenum}} +\par +\par} +\pard\plain \sect\sbkpage +\s1\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs36\kerning36\cgrid +File Index\par \pard\plain +{\tc \v File Index} +\pard\plain \s2\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs28\kerning28\cgrid +File List\par \pard\plain +{ +\pard\plain \s17\sa60\sb30\widctlpar\qj \fs22\cgrid Here is a list of all files with brief descriptions:} +{ +\par +\pard\plain \s71\li360\sa27\sb27\widctlpar\tqr\tldot\tx8640\adjustright \fs20\cgrid +{\b {\b ModbusRtu.h} } \tab {\field\fldedit {\*\fldinst PAGEREF AAAAAAAAAA \\*MERGEFORMAT}{\fldrslt pagenum}} +\par +\par} +\pard\plain \sect\sbkpage +\s1\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs36\kerning36\cgrid +Module Documentation{\tc \v Module Documentation} +\par \pard\plain +\pard\plain \s2\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs28\kerning28\cgrid +Modbus Object Instantiation/Initialization\par \pard\plain +{\tc\tcl2 \v Modbus Object Instantiation/Initialization} +{\xe \v Modbus Object Instantiation/Initialization} +{\bkmkstart AAAAAAAABQ} +{\bkmkend AAAAAAAABQ} +\pard\plain \s3\sb240\sa60\keepn\widctlpar\adjustright \b\f1\cgrid +Functions\par +\pard\plain + +{ +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +{\b Modbus::Modbus} ()\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Default Constructor for Master through Serial. }{ +}\par +}} +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +void {\b Modbus::begin} (long u32speed)\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Initialize class object. }{ +}\par +}} +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +void {\b Modbus::setID} (uint8_t u8id)\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +write new ID for the slave }{ +}\par +}} +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +uint8_t {\b Modbus::getID} ()\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +get slave ID between 1 and 247 }{ +}\par +}} +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +void {\b Modbus::setTimeOut} (uint16_t u16timeout)\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +write communication watch-dog timer }{ +}\par +}} +} +{\pard\widctlpar\brdrb\brdrs\brdrw5\brsp20 \adjustright \par} +\pard\plain \s3\sb240\sa60\keepn\widctlpar\adjustright \b\f1\cgrid +Detailed Description\par +\pard\plain +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +\par +}{\pard\widctlpar\brdrb\brdrs\brdrw5\brsp20 \adjustright \par} +\pard\plain \s3\sb240\sa60\keepn\widctlpar\adjustright \b\f1\cgrid +Function Documentation\par +\pard\plain +{\xe \v begin\:Modbus Object Instantiation/Initialization} +{\xe \v Modbus Object Instantiation/Initialization\:begin} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +void Modbus::begin (long {\i u32speed})}} +\par +{\bkmkstart AAAAAAAABR} +{\bkmkend AAAAAAAABR} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +\par +{ +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Initialize class object. }}\par +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Sets up the serial port using specified baud rate. Call once class has been instantiated, typically within setup().\par +{{\s5\sb90\sa30\keepn\widctlpar\adjustright \b\f1\fs20\cgrid +See Also:\par}\pard\plain \s62\li720\widctlpar\ql\adjustright \fs20\cgrid {\f2 http://arduino.cc/en/Serial/Begin#.Uy4CJ6aKlHY} \par +}{{\s5\sb90\sa30\keepn\widctlpar\adjustright \b\f1\fs20\cgrid +Parameters:\par} +\pard\plain \s61\li360\widctlpar\ql\adjustright \fs20\cgrid \trowd \trgaph108\trleft426\tblind426\trbrdrt\brdrs\brdrw10\brdrcf15 \trbrdrl\brdrs\brdrw10\brdrcf15 \trbrdrb\brdrs\brdrw10\brdrcf15 \trbrdrr\brdrs\brdrw10\brdrcf15 \trbrdrh\brdrs\brdrw10\brdrcf15 \trbrdrv\brdrs\brdrw10\brdrcf15 +\clvertalt\clbrdrt\brdrs\brdrw10\brdrcf15 \clbrdrl\brdrs\brdrw10\brdrcf15 \clbrdrb\brdrs\brdrw10\brdrcf15 \clbrdrr \brdrs\brdrw10\brdrcf15 \cltxlrtb \cellx2187 +\clvertalt\clbrdrt\brdrs\brdrw10\brdrcf15 \clbrdrl\brdrs\brdrw10\brdrcf15 \clbrdrb\brdrs\brdrw10\brdrcf15 \clbrdrr \brdrs\brdrw10\brdrcf15 \cltxlrtb \cellx8748 +\pard \widctlpar\intbl\adjustright +{{\i speed} \cell }{baud rate, in standard increments (300..115200) \cell } +{\row } +\trowd \trgaph108\trleft426\tblind426\trbrdrt\brdrs\brdrw10\brdrcf15 \trbrdrl\brdrs\brdrw10\brdrcf15 \trbrdrb\brdrs\brdrw10\brdrcf15 \trbrdrr\brdrs\brdrw10\brdrcf15 \trbrdrh\brdrs\brdrw10\brdrcf15 \trbrdrv\brdrs\brdrw10\brdrcf15 +\clvertalt\clbrdrt\brdrs\brdrw10\brdrcf15 \clbrdrl\brdrs\brdrw10\brdrcf15 \clbrdrb\brdrs\brdrw10\brdrcf15 \clbrdrr \brdrs\brdrw10\brdrcf15 \cltxlrtb \cellx2187 +\clvertalt\clbrdrt\brdrs\brdrw10\brdrcf15 \clbrdrl\brdrs\brdrw10\brdrcf15 \clbrdrb\brdrs\brdrw10\brdrcf15 \clbrdrr \brdrs\brdrw10\brdrcf15 \cltxlrtb \cellx8748 +\pard \widctlpar\intbl\adjustright +{{\i config} \cell }{data frame settings (data length, parity and stop bits) \cell } +{\row } +} +}{ +Definition at line 250 of file ModbusRtu.h.}\par +} +{\xe \v getID\:Modbus Object Instantiation/Initialization} +{\xe \v Modbus Object Instantiation/Initialization\:getID} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +uint8_t Modbus::getID ()}} +\par +{\bkmkstart AAAAAAAABS} +{\bkmkend AAAAAAAABS} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +\par +{ +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +get slave ID between 1 and 247 }}\par +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Method to read current slave ID address.\par +{{\s5\sb90\sa30\keepn\widctlpar\adjustright \b\f1\fs20\cgrid +Returns:\par}\pard\plain \s62\li720\widctlpar\ql\adjustright \fs20\cgrid u8id current slave address between 1 and 247 \par +}}{ +Definition at line 323 of file ModbusRtu.h.}\par +} +{\xe \v Modbus\:Modbus Object Instantiation/Initialization} +{\xe \v Modbus Object Instantiation/Initialization\:Modbus} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +Modbus::Modbus ()}} +\par +{\bkmkstart AAAAAAAABT} +{\bkmkend AAAAAAAABT} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +\par +{ +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Default Constructor for Master through Serial. }}\par +{ +Definition at line 204 of file ModbusRtu.h.}\par +} +{\xe \v setID\:Modbus Object Instantiation/Initialization} +{\xe \v Modbus Object Instantiation/Initialization\:setID} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +void Modbus::setID (uint8_t {\i u8id})}} +\par +{\bkmkstart AAAAAAAABU} +{\bkmkend AAAAAAAABU} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +\par +{ +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +write new ID for the slave }}\par +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Method to write a new slave ID address.\par +{{\s5\sb90\sa30\keepn\widctlpar\adjustright \b\f1\fs20\cgrid +Parameters:\par} +\pard\plain \s61\li360\widctlpar\ql\adjustright \fs20\cgrid \trowd \trgaph108\trleft426\tblind426\trbrdrt\brdrs\brdrw10\brdrcf15 \trbrdrl\brdrs\brdrw10\brdrcf15 \trbrdrb\brdrs\brdrw10\brdrcf15 \trbrdrr\brdrs\brdrw10\brdrcf15 \trbrdrh\brdrs\brdrw10\brdrcf15 \trbrdrv\brdrs\brdrw10\brdrcf15 +\clvertalt\clbrdrt\brdrs\brdrw10\brdrcf15 \clbrdrl\brdrs\brdrw10\brdrcf15 \clbrdrb\brdrs\brdrw10\brdrcf15 \clbrdrr \brdrs\brdrw10\brdrcf15 \cltxlrtb \cellx2187 +\clvertalt\clbrdrt\brdrs\brdrw10\brdrcf15 \clbrdrl\brdrs\brdrw10\brdrcf15 \clbrdrb\brdrs\brdrw10\brdrcf15 \clbrdrr \brdrs\brdrw10\brdrcf15 \cltxlrtb \cellx8748 +\pard \widctlpar\intbl\adjustright +{{\i u8id} \cell }{new slave address between 1 and 247 \cell } +{\row } +} +}{ +Definition at line 310 of file ModbusRtu.h.}\par +} +{\xe \v setTimeOut\:Modbus Object Instantiation/Initialization} +{\xe \v Modbus Object Instantiation/Initialization\:setTimeOut} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +void Modbus::setTimeOut (uint16_t {\i u16timeOut})}} +\par +{\bkmkstart AAAAAAAABV} +{\bkmkend AAAAAAAABV} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +\par +{ +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +write communication watch-dog timer }}\par +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Initialize time-out parameter.\par +Call once class has been instantiated, typically within setup(). The time-out timer is reset each time that there is a successful communication between Master and Slave. It works for both.\par +{{\s5\sb90\sa30\keepn\widctlpar\adjustright \b\f1\fs20\cgrid +Parameters:\par} +\pard\plain \s61\li360\widctlpar\ql\adjustright \fs20\cgrid \trowd \trgaph108\trleft426\tblind426\trbrdrt\brdrs\brdrw10\brdrcf15 \trbrdrl\brdrs\brdrw10\brdrcf15 \trbrdrb\brdrs\brdrw10\brdrcf15 \trbrdrr\brdrs\brdrw10\brdrcf15 \trbrdrh\brdrs\brdrw10\brdrcf15 \trbrdrv\brdrs\brdrw10\brdrcf15 +\clvertalt\clbrdrt\brdrs\brdrw10\brdrcf15 \clbrdrl\brdrs\brdrw10\brdrcf15 \clbrdrb\brdrs\brdrw10\brdrcf15 \clbrdrr \brdrs\brdrw10\brdrcf15 \cltxlrtb \cellx2187 +\clvertalt\clbrdrt\brdrs\brdrw10\brdrcf15 \clbrdrl\brdrs\brdrw10\brdrcf15 \clbrdrb\brdrs\brdrw10\brdrcf15 \clbrdrr \brdrs\brdrw10\brdrcf15 \cltxlrtb \cellx8748 +\pard \widctlpar\intbl\adjustright +{{\i time-out} \cell }{value (ms) \cell } +{\row } +} +}{ +Definition at line 338 of file ModbusRtu.h.}\par +} +\par \pard\plain +\pard\plain \s2\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs28\kerning28\cgrid +Modbus Object Management\par \pard\plain +{\tc\tcl2 \v Modbus Object Management} +{\xe \v Modbus Object Management} +{\bkmkstart AAAAAAAABW} +{\bkmkend AAAAAAAABW} +\pard\plain \s3\sb240\sa60\keepn\widctlpar\adjustright \b\f1\cgrid +Functions\par +\pard\plain + +{ +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +boolean {\b Modbus::getTimeOutState} ()\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +get communication watch-dog timer state }{ +}\par +}} +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +int8_t {\b Modbus::query} ({\b modbus_t} telegram)\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +only for master }{ +}\par +}} +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +int8_t {\b Modbus::poll} ()\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +cyclic poll for master }{ +}\par +}} +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +int8_t {\b Modbus::poll} (uint16_t *regs, uint8_t u8size)\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +cyclic poll for slave }{ +}\par +}} +} +{\pard\widctlpar\brdrb\brdrs\brdrw5\brsp20 \adjustright \par} +\pard\plain \s3\sb240\sa60\keepn\widctlpar\adjustright \b\f1\cgrid +Detailed Description\par +\pard\plain +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +\par +}{\pard\widctlpar\brdrb\brdrs\brdrw5\brsp20 \adjustright \par} +\pard\plain \s3\sb240\sa60\keepn\widctlpar\adjustright \b\f1\cgrid +Function Documentation\par +\pard\plain +{\xe \v getTimeOutState\:Modbus Object Management} +{\xe \v Modbus Object Management\:getTimeOutState} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +boolean Modbus::getTimeOutState ()}} +\par +{\bkmkstart AAAAAAAABX} +{\bkmkend AAAAAAAABX} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +\par +{ +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +get communication watch-dog timer state }}\par +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Return communication Watchdog state. It could be usefull to reset outputs if the watchdog is fired.\par +{{\s5\sb90\sa30\keepn\widctlpar\adjustright \b\f1\fs20\cgrid +Returns:\par}\pard\plain \s62\li720\widctlpar\ql\adjustright \fs20\cgrid TRUE if millis() > u32timeOut \par +}}{ +Definition at line 350 of file ModbusRtu.h.}\par +} +{\xe \v poll\:Modbus Object Management} +{\xe \v Modbus Object Management\:poll} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +int8_t Modbus::poll ()}} +\par +{\bkmkstart AAAAAAAABY} +{\bkmkend AAAAAAAABY} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +\par +{ +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +cyclic poll for master }}\par +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +*** Only for {\b Modbus} Master *** This method checks if there is any incoming answer if pending. If there is no answer, it would change Master state to COM_IDLE. This method must be called only at loop section. Avoid any delay() function.\par +Any incoming data would be redirected to au16regs pointer, as defined in its {\b modbus_t} query telegram.\par +nothing \par +{{\s5\sb90\sa30\keepn\widctlpar\adjustright \b\f1\fs20\cgrid +Returns:\par}\pard\plain \s62\li720\widctlpar\ql\adjustright \fs20\cgrid errors counter \par +}}{ +Definition at line 513 of file ModbusRtu.h.}\par +} +{\xe \v poll\:Modbus Object Management} +{\xe \v Modbus Object Management\:poll} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +int8_t Modbus::poll (uint16_t * {\i regs}, uint8_t {\i u8size})}} +\par +{\bkmkstart AAAAAAAABZ} +{\bkmkend AAAAAAAABZ} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +\par +{ +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +cyclic poll for slave }}\par +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +*** Only for {\b Modbus} Slave *** This method checks if there is any incoming query Afterwards, it would shoot a validation routine plus a register query Avoid any delay() function !!!! After a successful frame between the Master and the Slave, the time-out timer is reset.\par +{{\s5\sb90\sa30\keepn\widctlpar\adjustright \b\f1\fs20\cgrid +Parameters:\par} +\pard\plain \s61\li360\widctlpar\ql\adjustright \fs20\cgrid \trowd \trgaph108\trleft426\tblind426\trbrdrt\brdrs\brdrw10\brdrcf15 \trbrdrl\brdrs\brdrw10\brdrcf15 \trbrdrb\brdrs\brdrw10\brdrcf15 \trbrdrr\brdrs\brdrw10\brdrcf15 \trbrdrh\brdrs\brdrw10\brdrcf15 \trbrdrv\brdrs\brdrw10\brdrcf15 +\clvertalt\clbrdrt\brdrs\brdrw10\brdrcf15 \clbrdrl\brdrs\brdrw10\brdrcf15 \clbrdrb\brdrs\brdrw10\brdrcf15 \clbrdrr \brdrs\brdrw10\brdrcf15 \cltxlrtb \cellx2187 +\clvertalt\clbrdrt\brdrs\brdrw10\brdrcf15 \clbrdrl\brdrs\brdrw10\brdrcf15 \clbrdrb\brdrs\brdrw10\brdrcf15 \clbrdrr \brdrs\brdrw10\brdrcf15 \cltxlrtb \cellx8748 +\pard \widctlpar\intbl\adjustright +{{\i *regs} \cell }{register table for communication exchange \cell } +{\row } +\trowd \trgaph108\trleft426\tblind426\trbrdrt\brdrs\brdrw10\brdrcf15 \trbrdrl\brdrs\brdrw10\brdrcf15 \trbrdrb\brdrs\brdrw10\brdrcf15 \trbrdrr\brdrs\brdrw10\brdrcf15 \trbrdrh\brdrs\brdrw10\brdrcf15 \trbrdrv\brdrs\brdrw10\brdrcf15 +\clvertalt\clbrdrt\brdrs\brdrw10\brdrcf15 \clbrdrl\brdrs\brdrw10\brdrcf15 \clbrdrb\brdrs\brdrw10\brdrcf15 \clbrdrr \brdrs\brdrw10\brdrcf15 \cltxlrtb \cellx2187 +\clvertalt\clbrdrt\brdrs\brdrw10\brdrcf15 \clbrdrl\brdrs\brdrw10\brdrcf15 \clbrdrb\brdrs\brdrw10\brdrcf15 \clbrdrr \brdrs\brdrw10\brdrcf15 \cltxlrtb \cellx8748 +\pard \widctlpar\intbl\adjustright +{{\i u8size} \cell }{size of the register table \cell } +{\row } +} +{{\s5\sb90\sa30\keepn\widctlpar\adjustright \b\f1\fs20\cgrid +Returns:\par}\pard\plain \s62\li720\widctlpar\ql\adjustright \fs20\cgrid 0 if no query, 1..4 if communication error, >4 if correct query processed \par +}}{ +Definition at line 588 of file ModbusRtu.h.}\par +} +{\xe \v query\:Modbus Object Management} +{\xe \v Modbus Object Management\:query} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +int8_t Modbus::query ({\b modbus_t} {\i telegram})}} +\par +{\bkmkstart AAAAAAAACA} +{\bkmkend AAAAAAAACA} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +\par +{ +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +only for master }}\par +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +*** Only {\b Modbus} Master *** Generate a query to an slave with a {\b modbus_t} telegram structure The Master must be in COM_IDLE mode. After it, its state would be COM_WAITING. This method has to be called only in loop() section.\par +{{\s5\sb90\sa30\keepn\widctlpar\adjustright \b\f1\fs20\cgrid +See Also:\par}\pard\plain \s62\li720\widctlpar\ql\adjustright \fs20\cgrid {\b modbus_t} \par +}{{\s5\sb90\sa30\keepn\widctlpar\adjustright \b\f1\fs20\cgrid +Parameters:\par} +\pard\plain \s61\li360\widctlpar\ql\adjustright \fs20\cgrid \trowd \trgaph108\trleft426\tblind426\trbrdrt\brdrs\brdrw10\brdrcf15 \trbrdrl\brdrs\brdrw10\brdrcf15 \trbrdrb\brdrs\brdrw10\brdrcf15 \trbrdrr\brdrs\brdrw10\brdrcf15 \trbrdrh\brdrs\brdrw10\brdrcf15 \trbrdrv\brdrs\brdrw10\brdrcf15 +\clvertalt\clbrdrt\brdrs\brdrw10\brdrcf15 \clbrdrl\brdrs\brdrw10\brdrcf15 \clbrdrb\brdrs\brdrw10\brdrcf15 \clbrdrr \brdrs\brdrw10\brdrcf15 \cltxlrtb \cellx2187 +\clvertalt\clbrdrt\brdrs\brdrw10\brdrcf15 \clbrdrl\brdrs\brdrw10\brdrcf15 \clbrdrb\brdrs\brdrw10\brdrcf15 \clbrdrr \brdrs\brdrw10\brdrcf15 \cltxlrtb \cellx8748 +\pard \widctlpar\intbl\adjustright +{{\i {\b modbus_t}} \cell }{modbus telegram structure (id, fct, ...)\cell } +{\row } +} +{{\s5\sb90\sa30\keepn\widctlpar\adjustright \b\f1\fs20\cgrid +Todo:\par}\pard\plain \s62\li720\widctlpar\ql\adjustright \fs20\cgrid finish function 15 \par +} +}{ +Definition at line 425 of file ModbusRtu.h.}\par +} +\par \pard\plain +\pard\plain \s2\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs28\kerning28\cgrid +Modbus Buffer Management\par \pard\plain +{\tc\tcl2 \v Modbus Buffer Management} +{\xe \v Modbus Buffer Management} +{\bkmkstart AAAAAAAACB} +{\bkmkend AAAAAAAACB} +\pard\plain \s3\sb240\sa60\keepn\widctlpar\adjustright \b\f1\cgrid +Functions\par +\pard\plain + +{ +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +uint16_t {\b Modbus::getInCnt} ()\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +number of incoming messages }{ +}\par +}} +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +uint16_t {\b Modbus::getOutCnt} ()\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +number of outcoming messages }{ +}\par +}} +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +uint16_t {\b Modbus::getErrCnt} ()\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +error counter }{ +}\par +}} +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +uint8_t {\b Modbus::getState} ()\par +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +uint8_t {\b Modbus::getLastError} ()\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +get last error message }{ +}\par +}} +} +{\pard\widctlpar\brdrb\brdrs\brdrw5\brsp20 \adjustright \par} +\pard\plain \s3\sb240\sa60\keepn\widctlpar\adjustright \b\f1\cgrid +Detailed Description\par +\pard\plain +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +\par +}{\pard\widctlpar\brdrb\brdrs\brdrw5\brsp20 \adjustright \par} +\pard\plain \s3\sb240\sa60\keepn\widctlpar\adjustright \b\f1\cgrid +Function Documentation\par +\pard\plain +{\xe \v getErrCnt\:Modbus Buffer Management} +{\xe \v Modbus Buffer Management\:getErrCnt} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +uint16_t Modbus::getErrCnt ()}} +\par +{\bkmkstart AAAAAAAACC} +{\bkmkend AAAAAAAACC} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +\par +{ +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +error counter }}\par +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Get errors counter value This can be useful to diagnose communication.\par +{{\s5\sb90\sa30\keepn\widctlpar\adjustright \b\f1\fs20\cgrid +Returns:\par}\pard\plain \s62\li720\widctlpar\ql\adjustright \fs20\cgrid errors counter \par +}}{ +Definition at line 386 of file ModbusRtu.h.}\par +} +{\xe \v getInCnt\:Modbus Buffer Management} +{\xe \v Modbus Buffer Management\:getInCnt} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +uint16_t Modbus::getInCnt ()}} +\par +{\bkmkstart AAAAAAAACD} +{\bkmkend AAAAAAAACD} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +\par +{ +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +number of incoming messages }}\par +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Get input messages counter value This can be useful to diagnose communication.\par +{{\s5\sb90\sa30\keepn\widctlpar\adjustright \b\f1\fs20\cgrid +Returns:\par}\pard\plain \s62\li720\widctlpar\ql\adjustright \fs20\cgrid input messages counter \par +}}{ +Definition at line 362 of file ModbusRtu.h.}\par +} +{\xe \v getLastError\:Modbus Buffer Management} +{\xe \v Modbus Buffer Management\:getLastError} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +uint8_t Modbus::getLastError ()}} +\par +{\bkmkstart AAAAAAAACE} +{\bkmkend AAAAAAAACE} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +\par +{ +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +get last error message }}\par +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Get the last error in the protocol processor\par +NO_REPLY = 255 Time-out \par +{{\s5\sb90\sa30\keepn\widctlpar\adjustright \b\f1\fs20\cgrid +Returns:\par}\pard\plain \s62\li720\widctlpar\ql\adjustright \fs20\cgrid EXC_FUNC_CODE = 1 Function code not available \par +EXC_ADDR_RANGE = 2 Address beyond available space for {\b Modbus} registers \par +EXC_REGS_QUANT = 3 Coils or registers number beyond the available space \par +}}{ +Definition at line 409 of file ModbusRtu.h.}\par +} +{\xe \v getOutCnt\:Modbus Buffer Management} +{\xe \v Modbus Buffer Management\:getOutCnt} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +uint16_t Modbus::getOutCnt ()}} +\par +{\bkmkstart AAAAAAAACF} +{\bkmkend AAAAAAAACF} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +\par +{ +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +number of outcoming messages }}\par +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Get transmitted messages counter value This can be useful to diagnose communication.\par +{{\s5\sb90\sa30\keepn\widctlpar\adjustright \b\f1\fs20\cgrid +Returns:\par}\pard\plain \s62\li720\widctlpar\ql\adjustright \fs20\cgrid transmitted messages counter \par +}}{ +Definition at line 374 of file ModbusRtu.h.}\par +} +{\xe \v getState\:Modbus Buffer Management} +{\xe \v Modbus Buffer Management\:getState} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +uint8_t Modbus::getState ()}} +\par +{\bkmkstart AAAAAAAACG} +{\bkmkend AAAAAAAACG} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Get modbus master state\par +{{\s5\sb90\sa30\keepn\widctlpar\adjustright \b\f1\fs20\cgrid +Returns:\par}\pard\plain \s62\li720\widctlpar\ql\adjustright \fs20\cgrid = 0 IDLE, = 1 WAITING FOR ANSWER \par +}}{ +Definition at line 396 of file ModbusRtu.h.}\par +} +\par \pard\plain +\pard\plain \s2\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs28\kerning28\cgrid +Modbus Function Codes for Discrete Coils/Inputs\par \pard\plain +{\tc\tcl2 \v Modbus Function Codes for Discrete Coils/Inputs} +{\xe \v Modbus Function Codes for Discrete Coils/Inputs} +{\bkmkstart AAAAAAAACH} +{\bkmkend AAAAAAAACH} +{\pard\widctlpar\brdrb\brdrs\brdrw5\brsp20 \adjustright \par} +\pard\plain \s3\sb240\sa60\keepn\widctlpar\adjustright \b\f1\cgrid +Detailed Description\par +\pard\plain +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +\par +}\par \pard\plain +\pard\plain \s2\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs28\kerning28\cgrid +Modbus Function Codes for Holding/Input Registers\par \pard\plain +{\tc\tcl2 \v Modbus Function Codes for Holding/Input Registers} +{\xe \v Modbus Function Codes for Holding/Input Registers} +{\bkmkstart AAAAAAAACI} +{\bkmkend AAAAAAAACI} +{\pard\widctlpar\brdrb\brdrs\brdrw5\brsp20 \adjustright \par} +\pard\plain \s3\sb240\sa60\keepn\widctlpar\adjustright \b\f1\cgrid +Detailed Description\par +\pard\plain +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +\par +} +\pard\plain \sect\sbkpage +\s1\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs36\kerning36\cgrid +Class Documentation{\tc \v Class Documentation} +\par \pard\plain +\pard\plain \s2\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs28\kerning28\cgrid +Modbus Class Reference\par \pard\plain +{\tc\tcl2 \v Modbus} +{\xe \v Modbus} +{\bkmkstart AAAAAAAACJ} +{\bkmkend AAAAAAAACJ} +\par +{ +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Arduino class library for communicating with {\b Modbus} devices over USB/RS232/485 (via RTU protocol). }}\par +{ +{\f2 #include }}\par +\pard\plain \s3\sb240\sa60\keepn\widctlpar\adjustright \b\f1\cgrid +Public Member Functions\par +\pard\plain + +{ +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +{\b Modbus} ()\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Default Constructor for Master through Serial. }{ +}\par +}} +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +{\b Modbus} (uint8_t u8id, uint8_t u8serno)\par +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +{\b Modbus} (uint8_t u8id, uint8_t u8serno, uint8_t u8txenpin)\par +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +void {\b begin} (long u32speed)\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Initialize class object. }{ +}\par +}} +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +void {\b begin} ()\par +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +void {\b setTimeOut} (uint16_t u16timeout)\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +write communication watch-dog timer }{ +}\par +}} +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +uint16_t {\b getTimeOut} ()\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +get communication watch-dog timer value }{ +}\par +}} +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +boolean {\b getTimeOutState} ()\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +get communication watch-dog timer state }{ +}\par +}} +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +int8_t {\b query} ({\b modbus_t} telegram)\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +only for master }{ +}\par +}} +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +int8_t {\b poll} ()\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +cyclic poll for master }{ +}\par +}} +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +int8_t {\b poll} (uint16_t *regs, uint8_t u8size)\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +cyclic poll for slave }{ +}\par +}} +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +uint16_t {\b getInCnt} ()\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +number of incoming messages }{ +}\par +}} +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +uint16_t {\b getOutCnt} ()\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +number of outcoming messages }{ +}\par +}} +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +uint16_t {\b getErrCnt} ()\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +error counter }{ +}\par +}} +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +uint8_t {\b getID} ()\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +get slave ID between 1 and 247 }{ +}\par +}} +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +uint8_t {\b getState} ()\par +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +uint8_t {\b getLastError} ()\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +get last error message }{ +}\par +}} +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +void {\b setID} (uint8_t u8id)\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +write new ID for the slave }{ +}\par +}} +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +void {\b end} ()\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +finish any communication and release serial communication port }{ +}\par +}} +} +{\pard\widctlpar\brdrb\brdrs\brdrw5\brsp20 \adjustright \par} +\pard\plain \s3\sb240\sa60\keepn\widctlpar\adjustright \b\f1\cgrid +Detailed Description\par +\pard\plain +{ +\pard\plain \s17\sa60\sb30\widctlpar\qj \fs22\cgrid {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Arduino class library for communicating with {\b Modbus} devices over USB/RS232/485 (via RTU protocol). \par +}{ +Definition at line 141 of file ModbusRtu.h.}\par +} +{\pard\widctlpar\brdrb\brdrs\brdrw5\brsp20 \adjustright \par} +\pard\plain \s3\sb240\sa60\keepn\widctlpar\adjustright \b\f1\cgrid +Constructor & Destructor Documentation\par +\pard\plain +{\xe \v Modbus\:Modbus} +{\xe \v Modbus\:Modbus} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +Modbus::Modbus (uint8_t {\i u8id}, uint8_t {\i u8serno})}} +\par +{\bkmkstart AAAAAAAACK} +{\bkmkend AAAAAAAACK} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +\par +{ +Definition at line 218 of file ModbusRtu.h.}\par +} +{\xe \v Modbus\:Modbus} +{\xe \v Modbus\:Modbus} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +Modbus::Modbus (uint8_t {\i u8id}, uint8_t {\i u8serno}, uint8_t {\i u8txenpin})}} +\par +{\bkmkstart AAAAAAAACL} +{\bkmkend AAAAAAAACL} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +\par +{ +Definition at line 234 of file ModbusRtu.h.}\par +} +{\pard\widctlpar\brdrb\brdrs\brdrw5\brsp20 \adjustright \par} +\pard\plain \s3\sb240\sa60\keepn\widctlpar\adjustright \b\f1\cgrid +Member Function Documentation\par +\pard\plain +{\xe \v begin\:Modbus} +{\xe \v Modbus\:begin} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +void Modbus::begin ()}} +\par +{\bkmkstart AAAAAAAACM} +{\bkmkend AAAAAAAACM} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +\par +{ +Definition at line 299 of file ModbusRtu.h.}\par +} +{\xe \v end\:Modbus} +{\xe \v Modbus\:end} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +void Modbus::end ()}} +\par +{\bkmkstart AAAAAAAACN} +{\bkmkend AAAAAAAACN} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +\par +{ +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +finish any communication and release serial communication port }}\par +} +{\xe \v getTimeOut\:Modbus} +{\xe \v Modbus\:getTimeOut} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +uint16_t Modbus::getTimeOut ()}} +\par +{\bkmkstart AAAAAAAACO} +{\bkmkend AAAAAAAACO} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +\par +{ +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +get communication watch-dog timer value }}\par +} +{\pard\widctlpar\brdrb\brdrs\brdrw5\brsp20 \adjustright \par} +The documentation for this class was generated from the following file:{\par +\pard\plain \s81\fi-360\li720\widctlpar\jclisttab\tx720{\*\pn \pnlvlbody\ilvl0\ls2\pnrnot0\pndec }\ls2\adjustright \fs20\cgrid +{\b ModbusRtu.h}\par +}\par \pard\plain + +\pard\plain \sect\sbkpage +\s2\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs28\kerning28\cgrid +\pard\plain \s2\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs28\kerning28\cgrid +modbus_t Struct Reference\par \pard\plain +{\tc\tcl2 \v modbus_t} +{\xe \v modbus_t} +{\bkmkstart AAAAAAAACP} +{\bkmkend AAAAAAAACP} +\par +{ +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Master query structure: This includes all the necessary fields to make the Master generate a {\b Modbus} query. A Master may keep several of these structures and send them cyclically or use them according to program needs. }}\par +{ +{\f2 #include }}\par +\pard\plain \s3\sb240\sa60\keepn\widctlpar\adjustright \b\f1\cgrid +Public Attributes\par +\pard\plain + +{ +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +uint8_t {\b u8id}\par +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +uint8_t {\b u8fct}\par +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +uint16_t {\b u16RegAdd}\par +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +uint16_t {\b u16CoilsNo}\par +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +uint16_t * {\b au16reg}\par +} +{\pard\widctlpar\brdrb\brdrs\brdrw5\brsp20 \adjustright \par} +\pard\plain \s3\sb240\sa60\keepn\widctlpar\adjustright \b\f1\cgrid +Detailed Description\par +\pard\plain +{ +\pard\plain \s17\sa60\sb30\widctlpar\qj \fs22\cgrid {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Master query structure: This includes all the necessary fields to make the Master generate a {\b Modbus} query. A Master may keep several of these structures and send them cyclically or use them according to program needs. \par +}{ +Definition at line 48 of file ModbusRtu.h.}\par +} +{\pard\widctlpar\brdrb\brdrs\brdrw5\brsp20 \adjustright \par} +\pard\plain \s3\sb240\sa60\keepn\widctlpar\adjustright \b\f1\cgrid +Member Data Documentation\par +\pard\plain +{\xe \v au16reg\:modbus_t} +{\xe \v modbus_t\:au16reg} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +uint16_t* modbus_t::au16reg}} +\par +{\bkmkstart AAAAAAAACQ} +{\bkmkend AAAAAAAACQ} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Pointer to memory image in master \par +}{ +Definition at line 53 of file ModbusRtu.h.}\par +} +{\xe \v u16CoilsNo\:modbus_t} +{\xe \v modbus_t\:u16CoilsNo} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +uint16_t modbus_t::u16CoilsNo}} +\par +{\bkmkstart AAAAAAAACR} +{\bkmkend AAAAAAAACR} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Number of coils or registers to access \par +}{ +Definition at line 52 of file ModbusRtu.h.}\par +} +{\xe \v u16RegAdd\:modbus_t} +{\xe \v modbus_t\:u16RegAdd} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +uint16_t modbus_t::u16RegAdd}} +\par +{\bkmkstart AAAAAAAACS} +{\bkmkend AAAAAAAACS} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Address of the first register to access at slave/s \par +}{ +Definition at line 51 of file ModbusRtu.h.}\par +} +{\xe \v u8fct\:modbus_t} +{\xe \v modbus_t\:u8fct} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +uint8_t modbus_t::u8fct}} +\par +{\bkmkstart AAAAAAAACT} +{\bkmkend AAAAAAAACT} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Function code: 1, 2, 3, 4, 5, 6, 15 or 16 \par +}{ +Definition at line 50 of file ModbusRtu.h.}\par +} +{\xe \v u8id\:modbus_t} +{\xe \v modbus_t\:u8id} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +uint8_t modbus_t::u8id}} +\par +{\bkmkstart AAAAAAAACU} +{\bkmkend AAAAAAAACU} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Slave address between 1 and 247. 0 means broadcast \par +}{ +Definition at line 49 of file ModbusRtu.h.}\par +} +{\pard\widctlpar\brdrb\brdrs\brdrw5\brsp20 \adjustright \par} +The documentation for this struct was generated from the following file:{\par +\pard\plain \s81\fi-360\li720\widctlpar\jclisttab\tx720{\*\pn \pnlvlbody\ilvl0\ls2\pnrnot0\pndec }\ls2\adjustright \fs20\cgrid +{\b ModbusRtu.h}\par +} +\pard\plain \sect\sbkpage +\s1\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs36\kerning36\cgrid +File Documentation{\tc \v File Documentation} +\par \pard\plain +\pard\plain \s2\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs28\kerning28\cgrid +ModbusRtu.h File Reference\par \pard\plain +{\tc\tcl2 \v ModbusRtu.h} +{\xe \v ModbusRtu.h} +{\bkmkstart AAAAAAAAAA} +{\bkmkend AAAAAAAAAA} +\pard\plain \s3\sb240\sa60\keepn\widctlpar\adjustright \b\f1\cgrid +Classes\par +\pard\plain + +{ +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +struct {\b modbus_t}\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Master query structure: This includes all the necessary fields to make the Master generate a {\b Modbus} query. A Master may keep several of these structures and send them cyclically or use them according to program needs. }}} +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +class {\b Modbus}\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Arduino class library for communicating with {\b Modbus} devices over USB/RS232/485 (via RTU protocol). }}} +} +\pard\plain \s3\sb240\sa60\keepn\widctlpar\adjustright \b\f1\cgrid +Macros\par +\pard\plain + +{ +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +#define {\b T35}\~ 5\par +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +#define {\b MAX_BUFFER}\~ 64\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +maximum size for the communication buffer in bytes }{ +}\par +}} +} +\pard\plain \s3\sb240\sa60\keepn\widctlpar\adjustright \b\f1\cgrid +Enumerations\par +\pard\plain + +{ +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +enum \{ {\b RESPONSE_SIZE} = 6, +{\b EXCEPTION_SIZE} = 3, +{\b CHECKSUM_SIZE} = 2 + \}\par +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +enum {\b MESSAGE} \{ {\b ID} = 0, +{\b FUNC}, +{\b ADD_HI}, +{\b ADD_LO}, +{\b NB_HI}, +{\b NB_LO}, +{\b BYTE_CNT} + \}\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Indexes to telegram frame positions. }}} +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +enum {\b MB_FC} \{ {\b MB_FC_NONE} = 0, +{\b MB_FC_READ_COILS} = 1, +{\b MB_FC_READ_DISCRETE_INPUT} = 2, +{\b MB_FC_READ_REGISTERS} = 3, +{\b MB_FC_READ_INPUT_REGISTER} = 4, +{\b MB_FC_WRITE_COIL} = 5, +{\b MB_FC_WRITE_REGISTER} = 6, +{\b MB_FC_WRITE_MULTIPLE_COILS} = 15, +{\b MB_FC_WRITE_MULTIPLE_REGISTERS} = 16 + \}\par +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid {\i {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +{\b Modbus} function codes summary. These are the implement function codes either for Master or for Slave. }}} +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +enum {\b COM_STATES} \{ {\b COM_IDLE} = 0, +{\b COM_WAITING} = 1 + \}\par +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +enum {\b ERR_LIST} \{ {\b ERR_NOT_MASTER} = -1, +{\b ERR_POLLING} = -2, +{\b ERR_BUFF_OVERFLOW} = -3, +{\b ERR_BAD_CRC} = -4, +{\b ERR_EXCEPTION} = -5 + \}\par +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +enum \{ {\b NO_REPLY} = 255, +{\b EXC_FUNC_CODE} = 1, +{\b EXC_ADDR_RANGE} = 2, +{\b EXC_REGS_QUANT} = 3, +{\b EXC_EXECUTE} = 4 + \}\par +} +\pard\plain \s3\sb240\sa60\keepn\widctlpar\adjustright \b\f1\cgrid +Variables\par +\pard\plain + +{ +\pard\plain \s80\fi-360\li360\widctlpar\jclisttab\tx360{\*\pn \pnlvlbody\ilvl0\ls1\pnrnot0\pndec }\ls1\adjustright \fs20\cgrid +const unsigned char {\b fctsupported} []\par +} +{\pard\widctlpar\brdrb\brdrs\brdrw5\brsp20 \adjustright \par} +\pard\plain \s3\sb240\sa60\keepn\widctlpar\adjustright \b\f1\cgrid +Detailed Description\par +\pard\plain +{ +\pard\plain \s17\sa60\sb30\widctlpar\qj \fs22\cgrid {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +\par +{{\s5\sb90\sa30\keepn\widctlpar\adjustright \b\f1\fs20\cgrid +Version:\par}\pard\plain \s61\li360\widctlpar\ql\adjustright \fs20\cgrid 1.2 \par +}{{\s5\sb90\sa30\keepn\widctlpar\adjustright \b\f1\fs20\cgrid +Date:\par}\pard\plain \s61\li360\widctlpar\ql\adjustright \fs20\cgrid 2014.09.09 \par +}{{\s5\sb90\sa30\keepn\widctlpar\adjustright \b\f1\fs20\cgrid +Author:\par}\pard\plain \s61\li360\widctlpar\ql\adjustright \fs20\cgrid Samuel Marco i Armengol {\f2 sammarcoarmengol@gmail.com} \par +}Arduino library for communicating with {\b Modbus} devices over RS232/USB/485 via RTU protocol.\par +Further information: {\f2 http://modbus.org/} {\f2 http://modbus.org/docs/Modbus_over_serial_line_V1_02.pdf}\par +This library is free software; you can redistribute it and/or modify it under the terms of the GNU Lesser General Public License as published by the Free Software Foundation; version 2.1 of the License.\par +This library is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for more details.\par +You should have received a copy of the GNU Lesser General Public License along with this library; if not, write to the Free Software Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA \par +}{ +Definition in file {\b ModbusRtu.h}.}\par +} +{\pard\widctlpar\brdrb\brdrs\brdrw5\brsp20 \adjustright \par} +\pard\plain \s3\sb240\sa60\keepn\widctlpar\adjustright \b\f1\cgrid +Macro Definition Documentation\par +\pard\plain +{\xe \v MAX_BUFFER\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:MAX_BUFFER} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +#define MAX_BUFFER\~ 64}} +\par +{\bkmkstart AAAAAAAAAB} +{\bkmkend AAAAAAAAAB} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +\par +{ +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +maximum size for the communication buffer in bytes }}\par +{ +Definition at line 133 of file ModbusRtu.h.}\par +} +{\xe \v T35\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:T35} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +#define T35\~ 5}} +\par +{\bkmkstart AAAAAAAAAC} +{\bkmkend AAAAAAAAAC} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +\par +{ +Definition at line 132 of file ModbusRtu.h.}\par +} +{\pard\widctlpar\brdrb\brdrs\brdrw5\brsp20 \adjustright \par} +\pard\plain \s3\sb240\sa60\keepn\widctlpar\adjustright \b\f1\cgrid +Enumeration Type Documentation\par +\pard\plain +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +anonymous enum}} +\par +{\bkmkstart AAAAAAAAAD} +{\bkmkend AAAAAAAAAD} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +{{{\b \par +Enumerator}}\par +\pard\plain \s62\li720\widctlpar\ql\adjustright \fs20\cgrid {\xe \v RESPONSE_SIZE\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:RESPONSE_SIZE} +{\b {\i RESPONSE_SIZE{\bkmkstart AAAAAAAAAE} +{\bkmkend AAAAAAAAAE} +}} \par +{\xe \v EXCEPTION_SIZE\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:EXCEPTION_SIZE} +{\b {\i EXCEPTION_SIZE{\bkmkstart AAAAAAAAAF} +{\bkmkend AAAAAAAAAF} +}} \par +{\xe \v CHECKSUM_SIZE\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:CHECKSUM_SIZE} +{\b {\i CHECKSUM_SIZE{\bkmkstart AAAAAAAAAG} +{\bkmkend AAAAAAAAAG} +}} \par +}{ +Definition at line 57 of file ModbusRtu.h.}\par +} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +anonymous enum}} +\par +{\bkmkstart AAAAAAAAAH} +{\bkmkend AAAAAAAAAH} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +{{{\b \par +Enumerator}}\par +\pard\plain \s62\li720\widctlpar\ql\adjustright \fs20\cgrid {\xe \v NO_REPLY\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:NO_REPLY} +{\b {\i NO_REPLY{\bkmkstart AAAAAAAAAI} +{\bkmkend AAAAAAAAAI} +}} \par +{\xe \v EXC_FUNC_CODE\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:EXC_FUNC_CODE} +{\b {\i EXC_FUNC_CODE{\bkmkstart AAAAAAAAAJ} +{\bkmkend AAAAAAAAAJ} +}} \par +{\xe \v EXC_ADDR_RANGE\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:EXC_ADDR_RANGE} +{\b {\i EXC_ADDR_RANGE{\bkmkstart AAAAAAAAAK} +{\bkmkend AAAAAAAAAK} +}} \par +{\xe \v EXC_REGS_QUANT\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:EXC_REGS_QUANT} +{\b {\i EXC_REGS_QUANT{\bkmkstart AAAAAAAAAL} +{\bkmkend AAAAAAAAAL} +}} \par +{\xe \v EXC_EXECUTE\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:EXC_EXECUTE} +{\b {\i EXC_EXECUTE{\bkmkstart AAAAAAAAAM} +{\bkmkend AAAAAAAAAM} +}} \par +}{ +Definition at line 113 of file ModbusRtu.h.}\par +} +{\xe \v COM_STATES\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:COM_STATES} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +enum {\b COM_STATES}}} +\par +{\bkmkstart AAAAAAAAAN} +{\bkmkend AAAAAAAAAN} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +{{{\b \par +Enumerator}}\par +\pard\plain \s62\li720\widctlpar\ql\adjustright \fs20\cgrid {\xe \v COM_IDLE\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:COM_IDLE} +{\b {\i COM_IDLE{\bkmkstart AAAAAAAAAO} +{\bkmkend AAAAAAAAAO} +}} \par +{\xe \v COM_WAITING\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:COM_WAITING} +{\b {\i COM_WAITING{\bkmkstart AAAAAAAAAP} +{\bkmkend AAAAAAAAAP} +}} \par +}{ +Definition at line 99 of file ModbusRtu.h.}\par +} +{\xe \v ERR_LIST\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:ERR_LIST} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +enum {\b ERR_LIST}}} +\par +{\bkmkstart AAAAAAAAAQ} +{\bkmkend AAAAAAAAAQ} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +{{{\b \par +Enumerator}}\par +\pard\plain \s62\li720\widctlpar\ql\adjustright \fs20\cgrid {\xe \v ERR_NOT_MASTER\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:ERR_NOT_MASTER} +{\b {\i ERR_NOT_MASTER{\bkmkstart AAAAAAAAAR} +{\bkmkend AAAAAAAAAR} +}} \par +{\xe \v ERR_POLLING\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:ERR_POLLING} +{\b {\i ERR_POLLING{\bkmkstart AAAAAAAAAS} +{\bkmkend AAAAAAAAAS} +}} \par +{\xe \v ERR_BUFF_OVERFLOW\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:ERR_BUFF_OVERFLOW} +{\b {\i ERR_BUFF_OVERFLOW{\bkmkstart AAAAAAAAAT} +{\bkmkend AAAAAAAAAT} +}} \par +{\xe \v ERR_BAD_CRC\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:ERR_BAD_CRC} +{\b {\i ERR_BAD_CRC{\bkmkstart AAAAAAAAAU} +{\bkmkend AAAAAAAAAU} +}} \par +{\xe \v ERR_EXCEPTION\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:ERR_EXCEPTION} +{\b {\i ERR_EXCEPTION{\bkmkstart AAAAAAAAAV} +{\bkmkend AAAAAAAAAV} +}} \par +}{ +Definition at line 105 of file ModbusRtu.h.}\par +} +{\xe \v MB_FC\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:MB_FC} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +enum {\b MB_FC}}} +\par +{\bkmkstart AAAAAAAAAW} +{\bkmkend AAAAAAAAAW} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +\par +{ +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +{\b Modbus} function codes summary. These are the implement function codes either for Master or for Slave. }}\par +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +\par +{{\s5\sb90\sa30\keepn\widctlpar\adjustright \b\f1\fs20\cgrid +See Also:\par}\pard\plain \s62\li720\widctlpar\ql\adjustright \fs20\cgrid also {\b fctsupported} \par +also {\b modbus_t} \par +}}{{{\b Enumerator}}\par +\pard\plain \s62\li720\widctlpar\ql\adjustright \fs20\cgrid {\xe \v MB_FC_NONE\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:MB_FC_NONE} +{\b {\i MB_FC_NONE{\bkmkstart AAAAAAAAAX} +{\bkmkend AAAAAAAAAX} +}} {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +null operator \par +}{\xe \v MB_FC_READ_COILS\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:MB_FC_READ_COILS} +{\b {\i MB_FC_READ_COILS{\bkmkstart AAAAAAAAAY} +{\bkmkend AAAAAAAAAY} +}} {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +FCT=1 -> read coils or digital outputs \par +}{\xe \v MB_FC_READ_DISCRETE_INPUT\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:MB_FC_READ_DISCRETE_INPUT} +{\b {\i MB_FC_READ_DISCRETE_INPUT{\bkmkstart AAAAAAAAAZ} +{\bkmkend AAAAAAAAAZ} +}} {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +FCT=2 -> read digital inputs \par +}{\xe \v MB_FC_READ_REGISTERS\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:MB_FC_READ_REGISTERS} +{\b {\i MB_FC_READ_REGISTERS{\bkmkstart AAAAAAAABA} +{\bkmkend AAAAAAAABA} +}} {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +FCT=3 -> read registers or analog outputs \par +}{\xe \v MB_FC_READ_INPUT_REGISTER\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:MB_FC_READ_INPUT_REGISTER} +{\b {\i MB_FC_READ_INPUT_REGISTER{\bkmkstart AAAAAAAABB} +{\bkmkend AAAAAAAABB} +}} {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +FCT=4 -> read analog inputs \par +}{\xe \v MB_FC_WRITE_COIL\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:MB_FC_WRITE_COIL} +{\b {\i MB_FC_WRITE_COIL{\bkmkstart AAAAAAAABC} +{\bkmkend AAAAAAAABC} +}} {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +FCT=5 -> write single coil or output \par +}{\xe \v MB_FC_WRITE_REGISTER\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:MB_FC_WRITE_REGISTER} +{\b {\i MB_FC_WRITE_REGISTER{\bkmkstart AAAAAAAABD} +{\bkmkend AAAAAAAABD} +}} {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +FCT=6 -> write single register \par +}{\xe \v MB_FC_WRITE_MULTIPLE_COILS\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:MB_FC_WRITE_MULTIPLE_COILS} +{\b {\i MB_FC_WRITE_MULTIPLE_COILS{\bkmkstart AAAAAAAABE} +{\bkmkend AAAAAAAABE} +}} {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +FCT=15 -> write multiple coils or outputs \par +}{\xe \v MB_FC_WRITE_MULTIPLE_REGISTERS\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:MB_FC_WRITE_MULTIPLE_REGISTERS} +{\b {\i MB_FC_WRITE_MULTIPLE_REGISTERS{\bkmkstart AAAAAAAABF} +{\bkmkend AAAAAAAABF} +}} {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +FCT=16 -> write multiple registers \par +}}{ +Definition at line 87 of file ModbusRtu.h.}\par +} +{\xe \v MESSAGE\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:MESSAGE} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +enum {\b MESSAGE}}} +\par +{\bkmkstart AAAAAAAABG} +{\bkmkend AAAAAAAABG} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +\par +{ +{\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Indexes to telegram frame positions. }}\par +{{{\b Enumerator}}\par +\pard\plain \s62\li720\widctlpar\ql\adjustright \fs20\cgrid {\xe \v ID\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:ID} +{\b {\i ID{\bkmkstart AAAAAAAABH} +{\bkmkend AAAAAAAABH} +}} {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +ID field. \par +}{\xe \v FUNC\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:FUNC} +{\b {\i FUNC{\bkmkstart AAAAAAAABI} +{\bkmkend AAAAAAAABI} +}} {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Function code position. \par +}{\xe \v ADD_HI\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:ADD_HI} +{\b {\i ADD_HI{\bkmkstart AAAAAAAABJ} +{\bkmkend AAAAAAAABJ} +}} {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Address high byte. \par +}{\xe \v ADD_LO\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:ADD_LO} +{\b {\i ADD_LO{\bkmkstart AAAAAAAABK} +{\bkmkend AAAAAAAABK} +}} {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Address low byte. \par +}{\xe \v NB_HI\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:NB_HI} +{\b {\i NB_HI{\bkmkstart AAAAAAAABL} +{\bkmkend AAAAAAAABL} +}} {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Number of coils or registers high byte. \par +}{\xe \v NB_LO\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:NB_LO} +{\b {\i NB_LO{\bkmkstart AAAAAAAABM} +{\bkmkend AAAAAAAABM} +}} {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +Number of coils or registers low byte. \par +}{\xe \v BYTE_CNT\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:BYTE_CNT} +{\b {\i BYTE_CNT{\bkmkstart AAAAAAAABN} +{\bkmkend AAAAAAAABN} +}} {\s17\sa60\sb30\widctlpar\qj \fs22\cgrid +byte counter \par +}}{ +Definition at line 68 of file ModbusRtu.h.}\par +} +{\pard\widctlpar\brdrb\brdrs\brdrw5\brsp20 \adjustright \par} +\pard\plain \s3\sb240\sa60\keepn\widctlpar\adjustright \b\f1\cgrid +Variable Documentation\par +\pard\plain +{\xe \v fctsupported\:ModbusRtu.h} +{\xe \v ModbusRtu.h\:fctsupported} +\pard\plain \s4\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs20\cgrid { +{\b +const unsigned char fctsupported[]}} +\par +{\bkmkstart AAAAAAAABO} +{\bkmkend AAAAAAAABO} +{ +\pard\plain \s51\li360\sa60\sb30\qj\widctlpar\qj\adjustright \fs20\cgrid +{\b Initial value:}{ +\pard\plain \s41\li360\widctlpar\adjustright \shading1000\cbpat8 \f2\fs16\cgrid = \{ \par + MB_FC_READ_COILS,\par + MB_FC_READ_DISCRETE_INPUT,\par + MB_FC_READ_REGISTERS, \par + MB_FC_READ_INPUT_REGISTER,\par + MB_FC_WRITE_COIL,\par + MB_FC_WRITE_REGISTER, \par + MB_FC_WRITE_MULTIPLE_COILS,\par + MB_FC_WRITE_MULTIPLE_REGISTERS\par +\}\par +} +{ +Definition at line 121 of file ModbusRtu.h.}\par +} + +\pard\plain \sect\sbkpage +\s1\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs36\kerning36\cgrid +\s1\sb240\sa60\keepn\widctlpar\adjustright \b\f1\fs36\kerning36\cgrid Index\par +\pard\plain +{\tc \v Index} +{\field\fldedit {\*\fldinst INDEX \\c2 \\*MERGEFORMAT}{\fldrslt INDEX}} +} \ No newline at end of file diff --git a/software/firmware/libraries/modbus/examples/RS485_slave/RS485_slave.ino b/software/firmware/libraries/modbus/examples/RS485_slave/RS485_slave.ino new file mode 100644 index 0000000..2338ab0 --- /dev/null +++ b/software/firmware/libraries/modbus/examples/RS485_slave/RS485_slave.ino @@ -0,0 +1,34 @@ +/** + * Modbus slave example 3: + * The purpose of this example is to link a data array + * from the Arduino to an external device through RS485. + * + * Recommended Modbus Master: QModbus + * http://qmodbus.sourceforge.net/ + */ + +#include + +// assign the Arduino pin that must be connected to RE-DE RS485 transceiver +#define TXEN 4 + +// data array for modbus network sharing +uint16_t au16data[16] = { + 3, 1415, 9265, 4, 2, 7182, 28182, 8, 0, 0, 0, 0, 0, 0, 1, 65535 }; + +/** + * Modbus object declaration + * u8id : node id = 0 for master, = 1..247 for slave + * u8serno : serial port (use 0 for Serial) + * u8txenpin : 0 for RS-232 and USB-FTDI + * or any pin number > 1 for RS-485 + */ +Modbus slave(1,0,TXEN); // this is slave @1 and RS-485 + +void setup() { + slave.begin( 19200 ); // baud-rate at 19200 +} + +void loop() { + slave.poll( au16data, 16 ); +} diff --git a/software/firmware/libraries/modbus/examples/advanced_master/advanced_master.ino b/software/firmware/libraries/modbus/examples/advanced_master/advanced_master.ino new file mode 100644 index 0000000..484949b --- /dev/null +++ b/software/firmware/libraries/modbus/examples/advanced_master/advanced_master.ino @@ -0,0 +1,83 @@ +/** + * Modbus master example 2: + * The purpose of this example is to query several sets of data + * from an external Modbus slave device. + * The link media can be USB or RS232. + * + * Recommended Modbus slave: + * diagslave http://www.modbusdriver.com/diagslave.html + * + * In a Linux box, run + * "./diagslave /dev/ttyUSB0 -b 19200 -d 8 -s 1 -p none -m rtu -a 1" + * This is: + * serial port /dev/ttyUSB0 at 19200 baud 8N1 + * RTU mode and address @1 + */ + +#include + +uint16_t au16data[16]; //!< data array for modbus network sharing +uint8_t u8state; //!< machine state +uint8_t u8query; //!< pointer to message query + +/** + * Modbus object declaration + * u8id : node id = 0 for master, = 1..247 for slave + * u8serno : serial port (use 0 for Serial) + * u8txenpin : 0 for RS-232 and USB-FTDI + * or any pin number > 1 for RS-485 + */ +Modbus master(0,0,0); // this is master and RS-232 or USB-FTDI + +/** + * This is an structe which contains a query to an slave device + */ +modbus_t telegram[2]; + +unsigned long u32wait; + +void setup() { + // telegram 0: read registers + telegram[0].u8id = 1; // slave address + telegram[0].u8fct = 3; // function code (this one is registers read) + telegram[0].u16RegAdd = 0; // start address in slave + telegram[0].u16CoilsNo = 4; // number of elements (coils or registers) to read + telegram[0].au16reg = au16data; // pointer to a memory array in the Arduino + + // telegram 1: write a single register + telegram[1].u8id = 1; // slave address + telegram[1].u8fct = 6; // function code (this one is write a single register) + telegram[1].u16RegAdd = 4; // start address in slave + telegram[1].u16CoilsNo = 1; // number of elements (coils or registers) to read + telegram[1].au16reg = au16data+4; // pointer to a memory array in the Arduino + + master.begin( 19200 ); // baud-rate at 19200 + master.setTimeOut( 5000 ); // if there is no answer in 5000 ms, roll over + u32wait = millis() + 1000; + u8state = u8query = 0; +} + +void loop() { + switch( u8state ) { + case 0: + if (millis() > u32wait) u8state++; // wait state + break; + case 1: + master.query( telegram[u8query] ); // send query (only once) + u8state++; + u8query++; + if (u8query > 2) u8query = 0; + break; + case 2: + master.poll(); // check incoming messages + if (master.getState() == COM_IDLE) { + u8state = 0; + u32wait = millis() + 1000; + } + break; + } + + au16data[4] = analogRead( 0 ); + +} + diff --git a/software/firmware/libraries/modbus/examples/advanced_slave/advanced_slave.ino b/software/firmware/libraries/modbus/examples/advanced_slave/advanced_slave.ino new file mode 100644 index 0000000..b56d65f --- /dev/null +++ b/software/firmware/libraries/modbus/examples/advanced_slave/advanced_slave.ino @@ -0,0 +1,119 @@ +/** + * Modbus slave example 2: + * The purpose of this example is to link the Arduino digital and analog + * pins to an external device. + * + * Recommended Modbus Master: QModbus + * http://qmodbus.sourceforge.net/ + */ + +#include +#define ID 1 + +Modbus slave(ID, 0, 0); // this is slave ID and RS-232 or USB-FTDI +boolean led; +int8_t state = 0; +unsigned long tempus; + +// data array for modbus network sharing +uint16_t au16data[9]; + +/** + * Setup procedure + */ +void setup() { + io_setup(); // I/O settings + + // start communication + slave.begin( 19200 ); + tempus = millis() + 100; + digitalWrite(13, HIGH ); +} + +/** + * Loop procedure + */ +void loop() { + // poll messages + // blink led pin on each valid message + state = slave.poll( au16data, 9 ); + + if (state > 4) { + tempus = millis() + 50; + digitalWrite(13, HIGH); + } + if (millis() > tempus) digitalWrite(13, LOW ); + + // link the Arduino pins to the Modbus array + io_poll(); +} + +/** + * pin maping: + * 2 - digital input + * 3 - digital input + * 4 - digital input + * 5 - digital input + * 6 - digital output + * 7 - digital output + * 8 - digital output + * 9 - digital output + * 10 - analog output + * 11 - analog output + * 14 - analog input + * 15 - analog input + * + * pin 13 is reserved to show a successful query + */ +void io_setup() { + // define i/o + pinMode(2, INPUT); + pinMode(3, INPUT); + pinMode(4, INPUT); + pinMode(5, INPUT); + pinMode(6, OUTPUT); + pinMode(7, OUTPUT); + pinMode(8, OUTPUT); + pinMode(9, OUTPUT); + pinMode(10, OUTPUT); + pinMode(11, OUTPUT); + pinMode(13, OUTPUT); + + digitalWrite(6, LOW ); + digitalWrite(7, LOW ); + digitalWrite(8, LOW ); + digitalWrite(9, LOW ); + digitalWrite(13, HIGH ); // this is for the UNO led pin + analogWrite(10, 0 ); + analogWrite(11, 0 ); +} + +/** + * Link between the Arduino pins and the Modbus array + */ +void io_poll() { + // get digital inputs -> au16data[0] + bitWrite( au16data[0], 0, digitalRead( 2 )); + bitWrite( au16data[0], 1, digitalRead( 3 )); + bitWrite( au16data[0], 2, digitalRead( 4 )); + bitWrite( au16data[0], 3, digitalRead( 5 )); + + // set digital outputs -> au16data[1] + digitalWrite( 6, bitRead( au16data[1], 0 )); + digitalWrite( 7, bitRead( au16data[1], 1 )); + digitalWrite( 8, bitRead( au16data[1], 2 )); + digitalWrite( 9, bitRead( au16data[1], 3 )); + + // set analog outputs + analogWrite( 10, au16data[2] ); + analogWrite( 11, au16data[3] ); + + // read analog inputs + au16data[4] = analogRead( 0 ); + au16data[5] = analogRead( 1 ); + + // diagnose communication + au16data[6] = slave.getInCnt(); + au16data[7] = slave.getOutCnt(); + au16data[8] = slave.getErrCnt(); +} diff --git a/software/firmware/libraries/modbus/examples/simple_master/simple_master.ino b/software/firmware/libraries/modbus/examples/simple_master/simple_master.ino new file mode 100644 index 0000000..947dda8 --- /dev/null +++ b/software/firmware/libraries/modbus/examples/simple_master/simple_master.ino @@ -0,0 +1,70 @@ +/** + * Modbus master example 1: + * The purpose of this example is to query an array of data + * from an external Modbus slave device. + * The link media can be USB or RS232. + * + * Recommended Modbus slave: + * diagslave http://www.modbusdriver.com/diagslave.html + * + * In a Linux box, run + * "./diagslave /dev/ttyUSB0 -b 19200 -d 8 -s 1 -p none -m rtu -a 1" + * This is: + * serial port /dev/ttyUSB0 at 19200 baud 8N1 + * RTU mode and address @1 + */ + +#include + +// data array for modbus network sharing +uint16_t au16data[16]; +uint8_t u8state; + +/** + * Modbus object declaration + * u8id : node id = 0 for master, = 1..247 for slave + * u8serno : serial port (use 0 for Serial) + * u8txenpin : 0 for RS-232 and USB-FTDI + * or any pin number > 1 for RS-485 + */ +Modbus master(0,0,0); // this is master and RS-232 or USB-FTDI + +/** + * This is an structe which contains a query to an slave device + */ +modbus_t telegram; + +unsigned long u32wait; + +void setup() { + master.begin( 19200 ); // baud-rate at 19200 + master.setTimeOut( 2000 ); // if there is no answer in 2000 ms, roll over + u32wait = millis() + 1000; + u8state = 0; +} + +void loop() { + switch( u8state ) { + case 0: + if (millis() > u32wait) u8state++; // wait state + break; + case 1: + telegram.u8id = 1; // slave address + telegram.u8fct = 3; // function code (this one is registers read) + telegram.u16RegAdd = 1; // start address in slave + telegram.u16CoilsNo = 4; // number of elements (coils or registers) to read + telegram.au16reg = au16data; // pointer to a memory array in the Arduino + + master.query( telegram ); // send query (only once) + u8state++; + break; + case 2: + master.poll(); // check incoming messages + if (master.getState() == COM_IDLE) { + u8state = 0; + u32wait = millis() + 100; + } + break; + } +} + diff --git a/software/firmware/libraries/modbus/examples/simple_slave/simple_slave.ino b/software/firmware/libraries/modbus/examples/simple_slave/simple_slave.ino new file mode 100644 index 0000000..ee56df2 --- /dev/null +++ b/software/firmware/libraries/modbus/examples/simple_slave/simple_slave.ino @@ -0,0 +1,32 @@ +/** + * Modbus slave example 1: + * The purpose of this example is to link a data array + * from the Arduino to an external device. + * + * Recommended Modbus Master: QModbus + * http://qmodbus.sourceforge.net/ + */ + +#include + +// data array for modbus network sharing +uint16_t au16data[16] = { + 3, 1415, 9265, 4, 2, 7182, 28182, 8, 0, 0, 0, 0, 0, 0, 1, 65535 }; + +/** + * Modbus object declaration + * u8id : node id = 0 for master, = 1..247 for slave + * u8serno : serial port (use 0 for Serial) + * u8txenpin : 0 for RS-232 and USB-FTDI + * or any pin number > 1 for RS-485 + */ +Modbus slave(1,0,0); // this is slave @1 and RS-232 or USB-FTDI + +void setup() { + slave.begin( 19200 ); // baud-rate at 19200 + //slave.begin( 19200, SERIAL_8E1 ); // 19200 baud, 8-bits, even, 1-bit stop +} + +void loop() { + slave.poll( au16data, 16 ); +} diff --git a/software/firmware/libraries/modbus/examples/software_serial_simple_master/software_serial_simple_master.ino b/software/firmware/libraries/modbus/examples/software_serial_simple_master/software_serial_simple_master.ino new file mode 100644 index 0000000..4944a80 --- /dev/null +++ b/software/firmware/libraries/modbus/examples/software_serial_simple_master/software_serial_simple_master.ino @@ -0,0 +1,101 @@ +/** + * Modbus master example 2: + * The purpose of this example is to query an array of data + * from an external Modbus slave device. + * This example is similar to "simple_master", but this example + * allows you to use software serial instead of hardware serial + * in case that you want to use D1 & D2 for other purposes. + * The link media can be USB or RS232. + + The circuit: + * software serial rx(D3) connect to tx pin of another device + * software serial tx(D4) connect to rx pin of another device + + * In this example, we will use two important methods so that we can use + * software serial. + * + * 1. Modbus::Modbus(uint8_t u8id) + * This is a constructor for a Master/Slave through USB/RS232C via software serial + * This constructor only specifies u8id (node address) and should be only + * used if you want to use software serial instead of hardware serial. + * This method is called if you create a ModBus object with only on parameter "u8id" + * u8id is the node address of the arduino that will be programmed on, + * 0 for master and 1..247 for slave + * for example: Modbus master(0); + * If you use this constructor you have to begin ModBus object by + * using "void Modbus::begin(SoftwareSerial *softPort, long u32speed)". + * + * 2. void Modbus::begin(SoftwareSerial *sPort, long u32speed) + * Initialize class object. + * This is the method you have to use if you construct the ModBus object by using + * Modbus::Modbus(uint8_t u8id) in order to use software serial and to avoid problems. + * You have to create a SoftwareSerial object on your own, as shown in the example. + * sPort is a pointer to your SoftwareSerial object, u32speed is the baud rate, in + * standard increments (300..115200) + + created long time ago + by smarmengol + modified 29 July 2016 + by Helium6072 + + This example code is in the public domain. + */ + +#include +#include + +// data array for modbus network sharing +uint16_t au16data[16]; +uint8_t u8state; + +/** + * Modbus object declaration + * u8id : node id = 0 for master, = 1..247 for slave + * u8serno : serial port (use 0 for Serial) + * u8txenpin : 0 for RS-232 and USB-FTDI + * or any pin number > 1 for RS-485 + */ +Modbus master(0); // this is master and RS-232 or USB-FTDI via software serial + +/** + * This is an structe which contains a query to an slave device + */ +modbus_t telegram; + +unsigned long u32wait; + +SoftwareSerial mySerial(3, 5);//Create a SoftwareSerial object so that we can use software serial. Search "software serial" on Arduino.cc to find out more details. + +void setup() { + Serial.begin(9600);//use the hardware serial if you want to connect to your computer via usb cable, etc. + master.begin( &mySerial, 9600 ); // begin the ModBus object. The first parameter is the address of your SoftwareSerial address. Do not forget the "&". 9600 means baud-rate at 9600 + master.setTimeOut( 2000 ); // if there is no answer in 2000 ms, roll over + u32wait = millis() + 1000; + u8state = 0; +} + +void loop() { + switch( u8state ) { + case 0: + if (millis() > u32wait) u8state++; // wait state + break; + case 1: + telegram.u8id = 104; // slave address + telegram.u8fct = 4; // function code (this one is registers read) + telegram.u16RegAdd = 3; // start address in slave + telegram.u16CoilsNo = 1; // number of elements (coils or registers) to read + telegram.au16reg = au16data; // pointer to a memory array in the Arduino + + master.query( telegram ); // send query (only once) + u8state++; + break; + case 2: + master.poll(); // check incoming messages + if (master.getState() == COM_IDLE) { + u8state = 0; + u32wait = millis() + 2000; + Serial.println(au16data[0]);//Or do something else! + } + break; + } +} diff --git a/software/firmware/libraries/modbus/keywords.txt b/software/firmware/libraries/modbus/keywords.txt new file mode 100644 index 0000000..0f7cc91 --- /dev/null +++ b/software/firmware/libraries/modbus/keywords.txt @@ -0,0 +1,30 @@ +####################################### +# Syntax Coloring Map For Modbus-Master-Slave +####################################### + +####################################### +# Datatypes (KEYWORD1) +####################################### +modbus_t KEYWORD1 + +####################################### +# Methods and Functions (KEYWORD2) +####################################### +begin KEYWORD2 +poll KEYWORD2 +getInCnt KEYWORD2 +getOutCnt KEYWORD2 +getErrCnt KEYWORD2 +getID KEYWORD2 +getState KEYWORD2 +query KEYWORD2 +setTimeOut KEYWORD2 + +####################################### +# Instances (KEYWORD2) +####################################### +Modbus KEYWORD2 + +####################################### +# Constants (LITERAL1) +####################################### diff --git a/software/firmware/tower/tower.ino b/software/firmware/tower/tower.ino index 95c2b6e..b170a39 100644 --- a/software/firmware/tower/tower.ino +++ b/software/firmware/tower/tower.ino @@ -1,9 +1,159 @@ +#include +#include +#include +#include + + +/* + Imu/data (Imu) + Imu/raw (Imu) + Imu/mag (MagneticField) + Imu/temp (Temperature) + + ---Raw Data (Imu/raw) --- + LinearAccel (x, y, z) + AngularVel (x, y, z); + + --- Filtered Data (Imu/data) --- + Orientation(z, y, z, w) + LinearAccel(x, y, z) + AngularVel(x, y, z) + + --- Mag Data (Imu/mag) --- + MagField(x, y, z) + + --- IMU Temp (Imu/temp) + temp (deg c) +*/ + +Adafruit_BNO055 bno = Adafruit_BNO055(WIRE_BUS, -1, BNO055_ADDRESS_A, I2C_MASTER, I2C_PINS_18_19, I2C_PULLUP_INT, I2C_RATE_100, I2C_OP_MODE_ISR); + + +#define gpsPort Serial3 +#define commsPort Serial2 +#define GPS_PORT_NAME "Serial3" + +const unsigned char ubxRate5Hz[] = { 0x06, 0x08, 0x06, 0x00, 200, 0x00, 0x01, 0x00, 0x01, 0x00 }; +const unsigned char ubxRate10Hz[] = { 0x06, 0x08, 0x06, 0x00, 100, 0x00, 0x01, 0x00, 0x01, 0x00 }; + +const char baud38400 [] = "PUBX,41,1,3,3,38400,0"; +const char baud57600 [] = "PUBX,41,1,3,3,57600,0"; +const char baud115200[] = "PUBX,41,1,3,3,115200,0"; + +imu::Vector<3> linear_accel; +imu::Vector<3> angular_vel; +imu::Quaternion quat; + +char current_byte = '$'; +String nmea_sentence = ""; +String output_sentence; + +char float_decimal_places = 8; + +void sendUBX( const unsigned char *progmemBytes, size_t len ) +{ + gpsPort.write( 0xB5 ); // SYNC1 + gpsPort.write( 0x62 ); // SYNC2 + + uint8_t a = 0, b = 0; + while (len-- > 0) { + uint8_t c = pgm_read_byte( progmemBytes++ ); + a += c; + b += a; + gpsPort.write( c ); + } + + gpsPort.write( a ); // CHECKSUM A + gpsPort.write( b ); // CHECKSUM B + +} + void setup() { // put your setup code here, to run once: + commsPort.begin(115200); + commsPort.transmitterEnable(6); + + delay(250); + gpsPort.begin(9600); + sendUBX( ubxRate5Hz, sizeof(ubxRate5Hz) ); + + if (!bno.begin()) { + /* There was a problem detecting the BNO055 ... check your connections */ + commsPort.print("Ooops, no BNO055 detected ... Check your wiring or I2C ADDR!"); + while (1); + } + bno.setExtCrystalUse(true); + + } void loop() { - // put your main code here, to run repeatedly: + + if (gpsPort.available() > 0 ) { + nmea_sentence = ""; + do { + if (gpsPort.available() > 0) { + current_byte = gpsPort.read(); + + if (current_byte != '\r' and current_byte != '\n') { + nmea_sentence += current_byte; + } + } + } while (current_byte != '\r'); + commsPort.println(nmea_sentence); + } + + quat = bno.getQuat(); + linear_accel = bno.getVector(Adafruit_BNO055::VECTOR_LINEARACCEL); + angular_vel = bno.getVector(Adafruit_BNO055::VECTOR_GYROSCOPE); + + commsPort.print("ox:"); + commsPort.print(quat.x(), float_decimal_places); + commsPort.print(","); + commsPort.print("oy:"); + commsPort.print(quat.y(), float_decimal_places); + commsPort.print(","); + commsPort.print("oz:"); + commsPort.print(quat.z(), float_decimal_places); + commsPort.print(","); + commsPort.print("ow:"); + commsPort.print(quat.w(), float_decimal_places); + + commsPort.print(","); + commsPort.print("lax:"); + commsPort.print(linear_accel.x(), float_decimal_places); + commsPort.print(","); + commsPort.print("lay:"); + commsPort.print(linear_accel.y(), float_decimal_places); + commsPort.print(","); + commsPort.print("laz:"); + commsPort.print(linear_accel.z(), float_decimal_places); + + + commsPort.print(","); + commsPort.print("avx:"); + commsPort.print(angular_vel.x(), float_decimal_places); + commsPort.print(","); + commsPort.print("avy:"); + commsPort.print(angular_vel.y(), float_decimal_places); + commsPort.print(","); + commsPort.print("avz:"); + commsPort.print(angular_vel.z(), float_decimal_places); + + commsPort.println(); + + // + // /* Display calibration status for each sensor. */ + // uint8_t system, gyro, accel, mag = 0; + // bno.getCalibration(&system, &gyro, &accel, &mag); + // commsPort.print("CALIBRATION: Sys="); + // commsPort.print(system, DEC); + // commsPort.print(" Gyro="); + // commsPort.print(gyro, DEC); + // commsPort.print(" Accel="); + // commsPort.print(accel, DEC); + // commsPort.print(" Mag="); + // commsPort.print(mag, DEC); } diff --git a/software/firmware/tower_pan_tilt/tower_pan_tilt.ino b/software/firmware/tower_pan_tilt/tower_pan_tilt.ino new file mode 100644 index 0000000..95c2b6e --- /dev/null +++ b/software/firmware/tower_pan_tilt/tower_pan_tilt.ino @@ -0,0 +1,9 @@ +void setup() { + // put your setup code here, to run once: + +} + +void loop() { + // put your main code here, to run repeatedly: + +} diff --git a/software/fragments/joystick_drive_test.py b/software/fragments/joystick_drive_test.py index 0f1bfaa..b4c3210 100644 --- a/software/fragments/joystick_drive_test.py +++ b/software/fragments/joystick_drive_test.py @@ -11,7 +11,6 @@ import logging from inputs import devices, GamePad import sys import time -import pygame import rospy from rover_drive.msg import RoverMotorDrive @@ -21,7 +20,7 @@ from rover_drive.msg import RoverMotorDrive # Global Variables ##################################### GAME_CONTROLLER_NAME = "Logitech Logitech Extreme 3D Pro" -CONTROLLER_DATA_UPDATE_FREQUENCY = 50 # Times per second +CONTROLLER_DATA_UPDATE_FREQUENCY = 100 # Times per second ##################################### @@ -122,8 +121,7 @@ class LogitechJoystick(QtCore.QThread): self.setup_controller_flag = False if self.data_acquisition_and_broadcast_flag: self.__get_controller_data() - - self.__broadcast_if_ready() + self.__broadcast_if_ready() # self.msleep(100) @@ -152,14 +150,19 @@ class LogitechJoystick(QtCore.QThread): def __broadcast_if_ready(self): - drive = RoverMotorDrive() + current_time = time.time() - axis = self.controller_states["left_stick_y_axis"] + if (current_time - self.last_time) > (1 / CONTROLLER_DATA_UPDATE_FREQUENCY): + drive = RoverMotorDrive() - drive.first_motor_direction = 1 if axis <= 512 else 0 - drive.first_motor_speed = min(abs(self.controller_states["left_stick_y_axis"] - 512) * 128, 65535) + axis = self.controller_states["left_stick_y_axis"] + + drive.first_motor_direction = 1 if axis <= 512 else 0 + drive.first_motor_speed = min(abs(self.controller_states["left_stick_y_axis"] - 512) * 128, 65535) + + self.pub.publish(drive) + self.last_time = current_time - self.pub.publish(drive) def on_kill_threads__slot(self):