Added package for the current testing gps. Also added a testing launcher folder

This commit is contained in:
2018-01-06 13:14:36 -08:00
parent f207446293
commit 2aaca71e91
111 changed files with 10550 additions and 0 deletions

View File

@@ -0,0 +1,37 @@
cmake_minimum_required(VERSION 2.8.3)
project(ublox_msgs)
find_package(catkin REQUIRED COMPONENTS message_generation ublox_serialization std_msgs sensor_msgs)
add_message_files(DIRECTORY msg)
generate_messages(DEPENDENCIES std_msgs sensor_msgs)
catkin_package(
INCLUDE_DIRS include
LIBRARIES ${PROJECT_NAME}
CATKIN_DEPENDS message_runtime ublox_serialization std_msgs sensor_msgs)
include_directories(${PROJECT_SOURCE_DIR}/include)
include_directories(${ublox_serialization_INCLUDE_DIRS})
add_library(${PROJECT_NAME} src/ublox_msgs.cpp)
add_dependencies(${PROJECT_NAME}
${${PROJECT_NAME}_EXPORTED_TARGETS}
${catkin_EXPORTED_TARGETS}
)
target_link_libraries(${PROJECT_NAME}
${catkin_LIBRARIES}
)
install(TARGETS ${PROJECT_NAME}
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
install(DIRECTORY include/
DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}
PATTERN ".svn" EXCLUDE
)

View File

@@ -0,0 +1,883 @@
//==============================================================================
// Copyright (c) 2012, Johannes Meyer, TU Darmstadt
// All rights reserved.
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of the Flight Systems and Automatic Control group,
// TU Darmstadt, nor the names of its contributors may be used to
// endorse or promote products derived from this software without
// specific prior written permission.
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//==============================================================================
#ifndef UBLOX_SERIALIZATION_UBLOX_MSGS_H
#define UBLOX_SERIALIZATION_UBLOX_MSGS_H
#include <ros/console.h>
#include <ublox/serialization.h>
#include <ublox_msgs/ublox_msgs.h>
///
/// This file declares custom serializers for u-blox messages with dynamic
/// lengths and messages where the get/set messages have different sizes, but
/// share the same parameters, such as CfgDAT.
///
namespace ublox {
///
/// @brief Serializes the CfgDAT message which has a different length for
/// get/set.
///
template <typename ContainerAllocator>
struct Serializer<ublox_msgs::CfgDAT_<ContainerAllocator> > {
typedef boost::call_traits<ublox_msgs::CfgDAT_<ContainerAllocator> >
CallTraits;
static void read(const uint8_t *data, uint32_t count,
typename CallTraits::reference m) {
ros::serialization::IStream stream(const_cast<uint8_t *>(data), count);
stream.next(m.datumNum);
stream.next(m.datumName);
stream.next(m.majA);
stream.next(m.flat);
stream.next(m.dX);
stream.next(m.dY);
stream.next(m.dZ);
stream.next(m.rotX);
stream.next(m.rotY);
stream.next(m.rotZ);
stream.next(m.scale);
}
static uint32_t serializedLength (typename CallTraits::param_type m) {
// this is the size of CfgDAT set messages
// serializedLength is only used for writes so this is ok
return 44;
}
static void write(uint8_t *data, uint32_t size,
typename CallTraits::param_type m) {
ros::serialization::OStream stream(data, size);
// ignores datumNum & datumName
stream.next(m.majA);
stream.next(m.flat);
stream.next(m.dX);
stream.next(m.dY);
stream.next(m.dZ);
stream.next(m.rotX);
stream.next(m.rotY);
stream.next(m.rotZ);
stream.next(m.scale);
}
};
///
/// @brief Serializes the CfgGNSS message which has a repeated block.
///
template <typename ContainerAllocator>
struct Serializer<ublox_msgs::CfgGNSS_<ContainerAllocator> > {
typedef ublox_msgs::CfgGNSS_<ContainerAllocator> Msg;
typedef boost::call_traits<Msg> CallTraits;
static void read(const uint8_t *data, uint32_t count,
typename CallTraits::reference m) {
ros::serialization::IStream stream(const_cast<uint8_t *>(data), count);
stream.next(m.msgVer);
stream.next(m.numTrkChHw);
stream.next(m.numTrkChUse);
stream.next(m.numConfigBlocks);
m.blocks.resize(m.numConfigBlocks);
for(std::size_t i = 0; i < m.blocks.size(); ++i)
ros::serialization::deserialize(stream, m.blocks[i]);
}
static uint32_t serializedLength (typename CallTraits::param_type m) {
return 4 + 8 * m.numConfigBlocks;
}
static void write(uint8_t *data, uint32_t size,
typename CallTraits::param_type m) {
if(m.blocks.size() != m.numConfigBlocks) {
ROS_ERROR("CfgGNSS numConfigBlocks must equal blocks size");
}
ros::serialization::OStream stream(data, size);
stream.next(m.msgVer);
stream.next(m.numTrkChHw);
stream.next(m.numTrkChUse);
stream.next(
static_cast<typename Msg::_numConfigBlocks_type>(m.blocks.size()));
for(std::size_t i = 0; i < m.blocks.size(); ++i)
ros::serialization::serialize(stream, m.blocks[i]);
}
};
///
/// @brief Serializes the CfgInf message which has a repeated block.
///
template <typename ContainerAllocator>
struct Serializer<ublox_msgs::CfgINF_<ContainerAllocator> > {
typedef boost::call_traits<ublox_msgs::CfgINF_<ContainerAllocator> >
CallTraits;
static void read(const uint8_t *data, uint32_t count,
typename CallTraits::reference m) {
ros::serialization::IStream stream(const_cast<uint8_t *>(data), count);
int num_blocks = count / 10;
m.blocks.resize(num_blocks);
for(std::size_t i = 0; i < num_blocks; ++i)
ros::serialization::deserialize(stream, m.blocks[i]);
}
static uint32_t serializedLength (typename CallTraits::param_type m) {
return 10 * m.blocks.size();
}
static void write(uint8_t *data, uint32_t size,
typename CallTraits::param_type m) {
ros::serialization::OStream stream(data, size);
for(std::size_t i = 0; i < m.blocks.size(); ++i)
ros::serialization::serialize(stream, m.blocks[i]);
}
};
///
/// @brief Serializes the Inf message which has a dynamic length string.
///
template <typename ContainerAllocator>
struct Serializer<ublox_msgs::Inf_<ContainerAllocator> > {
typedef boost::call_traits<ublox_msgs::Inf_<ContainerAllocator> > CallTraits;
static void read(const uint8_t *data, uint32_t count,
typename CallTraits::reference m) {
ros::serialization::IStream stream(const_cast<uint8_t *>(data), count);
m.str.resize(count);
for (int i = 0; i < count; ++i)
ros::serialization::deserialize(stream, m.str[i]);
}
static uint32_t serializedLength (typename CallTraits::param_type m) {
return m.str.size();
}
static void write(uint8_t *data, uint32_t size,
typename CallTraits::param_type m) {
ros::serialization::OStream stream(data, size);
for(std::size_t i = 0; i < m.str.size(); ++i)
ros::serialization::serialize(stream, m.str[i]);
}
};
///
/// @brief Serializes the MonVER message which has a repeated block.
///
template <typename ContainerAllocator>
struct Serializer<ublox_msgs::MonVER_<ContainerAllocator> > {
typedef ublox_msgs::MonVER_<ContainerAllocator> Msg;
typedef boost::call_traits<Msg> CallTraits;
static void read(const uint8_t *data, uint32_t count,
typename CallTraits::reference m) {
ros::serialization::IStream stream(const_cast<uint8_t *>(data), count);
stream.next(m.swVersion);
stream.next(m.hwVersion);
m.extension.clear();
int N = (count - 40) / 30;
m.extension.reserve(N);
typename Msg::_extension_type::value_type ext;
for (int i = 0; i < N; i++) {
// Read each extension string
stream.next(ext);
m.extension.push_back(ext);
}
}
static uint32_t serializedLength(typename CallTraits::param_type m) {
return 40 + (30 * m.extension.size());
}
static void write(uint8_t *data, uint32_t size,
typename CallTraits::param_type m) {
ros::serialization::OStream stream(data, size);
stream.next(m.swVersion);
stream.next(m.hwVersion);
for(std::size_t i = 0; i < m.extension.size(); ++i)
ros::serialization::serialize(stream, m.extension[i]);
}
};
///
/// @brief Serializes the NavDGPS message which has a repeated block.
///
template <typename ContainerAllocator>
struct Serializer<ublox_msgs::NavDGPS_<ContainerAllocator> > {
typedef ublox_msgs::NavDGPS_<ContainerAllocator> Msg;
typedef boost::call_traits<Msg> CallTraits;
static void read(const uint8_t *data, uint32_t count,
typename CallTraits::reference m) {
ros::serialization::IStream stream(const_cast<uint8_t *>(data), count);
stream.next(m.iTOW);
stream.next(m.age);
stream.next(m.baseId);
stream.next(m.baseHealth);
stream.next(m.numCh);
stream.next(m.status);
stream.next(m.reserved1);
m.sv.resize(m.numCh);
for(std::size_t i = 0; i < m.sv.size(); ++i)
ros::serialization::deserialize(stream, m.sv[i]);
}
static uint32_t serializedLength (typename CallTraits::param_type m) {
return 16 + 12 * m.numCh;
}
static void write(uint8_t *data, uint32_t size,
typename CallTraits::param_type m) {
if(m.sv.size() != m.numCh) {
ROS_ERROR("NavDGPS numCh must equal sv size");
}
ros::serialization::OStream stream(data, size);
stream.next(m.iTOW);
stream.next(m.age);
stream.next(m.baseId);
stream.next(m.baseHealth);
stream.next(static_cast<typename Msg::_numCh_type>(m.sv.size()));
stream.next(m.status);
stream.next(m.reserved1);
for(std::size_t i = 0; i < m.sv.size(); ++i)
ros::serialization::serialize(stream, m.sv[i]);
}
};
///
/// @brief Serializes the NavSBAS message which has a repeated block.
///
template <typename ContainerAllocator>
struct Serializer<ublox_msgs::NavSBAS_<ContainerAllocator> > {
typedef ublox_msgs::NavSBAS_<ContainerAllocator> Msg;
typedef boost::call_traits<Msg> CallTraits;
static void read(const uint8_t *data, uint32_t count,
typename CallTraits::reference m) {
ros::serialization::IStream stream(const_cast<uint8_t *>(data), count);
stream.next(m.iTOW);
stream.next(m.geo);
stream.next(m.mode);
stream.next(m.sys);
stream.next(m.service);
stream.next(m.cnt);
stream.next(m.reserved0);
m.sv.resize(m.cnt);
for(std::size_t i = 0; i < m.sv.size(); ++i)
ros::serialization::deserialize(stream, m.sv[i]);
}
static uint32_t serializedLength (typename CallTraits::param_type m) {
return 12 + 12 * m.cnt;
}
static void write(uint8_t *data, uint32_t size,
typename CallTraits::param_type m) {
if(m.sv.size() != m.cnt) {
ROS_ERROR("NavSBAS cnt must equal sv size");
}
ros::serialization::OStream stream(data, size);
stream.next(m.iTOW);
stream.next(m.geo);
stream.next(m.mode);
stream.next(m.sys);
stream.next(m.service);
stream.next(static_cast<typename Msg::_cnt_type>(m.sv.size()));
stream.next(m.reserved0);
for(std::size_t i = 0; i < m.sv.size(); ++i)
ros::serialization::serialize(stream, m.sv[i]);
}
};
///
/// @brief Serializes the NavSAT message which has a repeated block.
///
template <typename ContainerAllocator>
struct Serializer<ublox_msgs::NavSAT_<ContainerAllocator> > {
typedef ublox_msgs::NavSAT_<ContainerAllocator> Msg;
typedef boost::call_traits<Msg> CallTraits;
static void read(const uint8_t *data, uint32_t count,
typename CallTraits::reference m) {
ros::serialization::IStream stream(const_cast<uint8_t *>(data), count);
stream.next(m.iTOW);
stream.next(m.version);
stream.next(m.numSvs);
stream.next(m.reserved0);
m.sv.resize(m.numSvs);
for(std::size_t i = 0; i < m.sv.size(); ++i)
ros::serialization::deserialize(stream, m.sv[i]);
}
static uint32_t serializedLength (typename CallTraits::param_type m) {
return 8 + 12 * m.numSvs;
}
static void write(uint8_t *data, uint32_t size,
typename CallTraits::param_type m) {
if(m.sv.size() != m.numSvs) {
ROS_ERROR("NavSAT numSvs must equal sv size");
}
ros::serialization::OStream stream(data, size);
stream.next(m.iTOW);
stream.next(m.version);
stream.next(static_cast<typename Msg::_numSvs_type>(m.sv.size()));
stream.next(m.reserved0);
for(std::size_t i = 0; i < m.sv.size(); ++i)
ros::serialization::serialize(stream, m.sv[i]);
}
};
///
/// @brief Serializes the NavDGPS message which has a repeated block.
///
template <typename ContainerAllocator>
struct Serializer<ublox_msgs::NavSVINFO_<ContainerAllocator> > {
typedef ublox_msgs::NavSVINFO_<ContainerAllocator> Msg;
typedef boost::call_traits<Msg> CallTraits;
static void read(const uint8_t *data, uint32_t count,
typename CallTraits::reference m) {
ros::serialization::IStream stream(const_cast<uint8_t *>(data), count);
stream.next(m.iTOW);
stream.next(m.numCh);
stream.next(m.globalFlags);
stream.next(m.reserved2);
m.sv.resize(m.numCh);
for(std::size_t i = 0; i < m.sv.size(); ++i)
ros::serialization::deserialize(stream, m.sv[i]);
}
static uint32_t serializedLength (typename CallTraits::param_type m) {
return 8 + 12 * m.numCh;
}
static void write(uint8_t *data, uint32_t size,
typename CallTraits::param_type m) {
if(m.sv.size() != m.numCh) {
ROS_ERROR("NavSVINFO numCh must equal sv size");
}
ros::serialization::OStream stream(data, size);
stream.next(m.iTOW);
stream.next(static_cast<typename Msg::_numCh_type>(m.sv.size()));
stream.next(m.globalFlags);
stream.next(m.reserved2);
for(std::size_t i = 0; i < m.sv.size(); ++i)
ros::serialization::serialize(stream, m.sv[i]);
}
};
///
/// @brief Serializes the RxmRAW message which has a repeated block.
///
template <typename ContainerAllocator>
struct Serializer<ublox_msgs::RxmRAW_<ContainerAllocator> > {
typedef ublox_msgs::RxmRAW_<ContainerAllocator> Msg;
typedef boost::call_traits<Msg> CallTraits;
static void read(const uint8_t *data, uint32_t count,
typename CallTraits::reference m) {
ros::serialization::IStream stream(const_cast<uint8_t *>(data), count);
stream.next(m.rcvTOW);
stream.next(m.week);
stream.next(m.numSV);
stream.next(m.reserved1);
m.sv.resize(m.numSV);
for(std::size_t i = 0; i < m.sv.size(); ++i)
ros::serialization::deserialize(stream, m.sv[i]);
}
static uint32_t serializedLength (typename CallTraits::param_type m) {
return 8 + 24 * m.numSV;
}
static void write(uint8_t *data, uint32_t size,
typename CallTraits::param_type m) {
if(m.sv.size() != m.numSV) {
ROS_ERROR("RxmRAW numSV must equal sv size");
}
ros::serialization::OStream stream(data, size);
stream.next(m.rcvTOW);
stream.next(m.week);
stream.next(static_cast<typename Msg::_numSV_type>(m.sv.size()));
stream.next(m.reserved1);
for(std::size_t i = 0; i < m.sv.size(); ++i)
ros::serialization::serialize(stream, m.sv[i]);
}
};
///
/// @brief Serializes the RxmRAWX message which has a repeated block.
///
template <typename ContainerAllocator>
struct Serializer<ublox_msgs::RxmRAWX_<ContainerAllocator> > {
typedef ublox_msgs::RxmRAWX_<ContainerAllocator> Msg;
typedef boost::call_traits<Msg> CallTraits;
static void read(const uint8_t *data, uint32_t count,
typename CallTraits::reference m) {
ros::serialization::IStream stream(const_cast<uint8_t *>(data), count);
stream.next(m.rcvTOW);
stream.next(m.week);
stream.next(m.leapS);
stream.next(m.numMeas);
stream.next(m.recStat);
stream.next(m.version);
stream.next(m.reserved1);
m.meas.resize(m.numMeas);
for(std::size_t i = 0; i < m.meas.size(); ++i)
ros::serialization::deserialize(stream, m.meas[i]);
}
static uint32_t serializedLength (typename CallTraits::param_type m) {
return 16 + 32 * m.numMeas;
}
static void write(uint8_t *data, uint32_t size,
typename CallTraits::param_type m) {
if(m.meas.size() != m.numMeas) {
ROS_ERROR("RxmRAWX numMeas must equal meas size");
}
ros::serialization::OStream stream(data, size);
stream.next(m.rcvTOW);
stream.next(m.week);
stream.next(m.leapS);
stream.next(static_cast<typename Msg::_numMeas_type>(m.meas.size()));
stream.next(m.recStat);
stream.next(m.version);
stream.next(m.reserved1);
for(std::size_t i = 0; i < m.meas.size(); ++i)
ros::serialization::serialize(stream, m.meas[i]);
}
};
///
/// @brief Serializes the RxmSFRBX message which has a repeated block.
///
template <typename ContainerAllocator>
struct Serializer<ublox_msgs::RxmSFRBX_<ContainerAllocator> > {
typedef ublox_msgs::RxmSFRBX_<ContainerAllocator> Msg;
typedef boost::call_traits<Msg> CallTraits;
static void read(const uint8_t *data, uint32_t count,
typename CallTraits::reference m) {
ros::serialization::IStream stream(const_cast<uint8_t *>(data), count);
stream.next(m.gnssId);
stream.next(m.svId);
stream.next(m.reserved0);
stream.next(m.freqId);
stream.next(m.numWords);
stream.next(m.chn);
stream.next(m.version);
stream.next(m.reserved1);
m.dwrd.resize(m.numWords);
for(std::size_t i = 0; i < m.dwrd.size(); ++i)
ros::serialization::deserialize(stream, m.dwrd[i]);
}
static uint32_t serializedLength (typename CallTraits::param_type m) {
return 8 + 4 * m.numWords;
}
static void write(uint8_t *data, uint32_t size,
typename CallTraits::param_type m) {
if(m.dwrd.size() != m.numWords) {
ROS_ERROR("RxmSFRBX numWords must equal dwrd size");
}
ros::serialization::OStream stream(data, size);
stream.next(m.gnssId);
stream.next(m.svId);
stream.next(m.reserved0);
stream.next(m.freqId);
stream.next(static_cast<typename Msg::_numWords_type>(m.dwrd.size()));
stream.next(m.chn);
stream.next(m.version);
stream.next(m.reserved1);
for(std::size_t i = 0; i < m.dwrd.size(); ++i)
ros::serialization::serialize(stream, m.dwrd[i]);
}
};
///
/// @brief Serializes the RxmSVSI message which has a repeated block.
///
template <typename ContainerAllocator>
struct Serializer<ublox_msgs::RxmSVSI_<ContainerAllocator> > {
typedef ublox_msgs::RxmSVSI_<ContainerAllocator> Msg;
typedef boost::call_traits<Msg> CallTraits;
static void read(const uint8_t *data, uint32_t count,
typename CallTraits::reference m) {
ros::serialization::IStream stream(const_cast<uint8_t *>(data), count);
stream.next(m.iTOW);
stream.next(m.week);
stream.next(m.numVis);
stream.next(m.numSV);
m.sv.resize(m.numSV);
for(std::size_t i = 0; i < m.sv.size(); ++i)
ros::serialization::deserialize(stream, m.sv[i]);
}
static uint32_t serializedLength (typename CallTraits::param_type m) {
return 8 + 6 * m.numSV;
}
static void write(uint8_t *data, uint32_t size,
typename CallTraits::param_type m) {
if(m.sv.size() != m.numSV) {
ROS_ERROR("RxmSVSI numSV must equal sv size");
}
ros::serialization::OStream stream(data, size);
stream.next(m.iTOW);
stream.next(m.week);
stream.next(m.numVis);
stream.next(static_cast<typename Msg::_numSV_type>(m.sv.size()));
for(std::size_t i = 0; i < m.sv.size(); ++i)
ros::serialization::serialize(stream, m.sv[i]);
}
};
///
/// @brief Serializes the RxmALM message which has a repeated block.
///
template <typename ContainerAllocator>
struct Serializer<ublox_msgs::RxmALM_<ContainerAllocator> > {
typedef ublox_msgs::RxmALM_<ContainerAllocator> Msg;
typedef boost::call_traits<Msg> CallTraits;
static void read(const uint8_t *data, uint32_t count,
typename CallTraits::reference m) {
ros::serialization::IStream stream(const_cast<uint8_t *>(data), count);
stream.next(m.svid);
stream.next(m.week);
m.dwrd.clear();
if(count == 40) {
typename Msg::_dwrd_type::value_type temp;
m.dwrd.resize(8);
for(std::size_t i = 0; i < 8; ++i) {
stream.next(temp);
m.dwrd.push_back(temp);
}
}
}
static uint32_t serializedLength (typename CallTraits::param_type m) {
return 8 + (4 * m.dwrd.size());
}
static void write(uint8_t *data, uint32_t size,
typename CallTraits::param_type m) {
ros::serialization::OStream stream(data, size);
stream.next(m.svid);
stream.next(m.week);
for(std::size_t i = 0; i < m.dwrd.size(); ++i)
ros::serialization::serialize(stream, m.dwrd[i]);
}
};
///
/// @brief Serializes the RxmEPH message which has a repeated block.
///
template <typename ContainerAllocator>
struct Serializer<ublox_msgs::RxmEPH_<ContainerAllocator> >
{
typedef ublox_msgs::RxmEPH_<ContainerAllocator> Msg;
typedef boost::call_traits<Msg> CallTraits;
static void read(const uint8_t *data, uint32_t count,
typename CallTraits::reference m) {
ros::serialization::IStream stream(const_cast<uint8_t *>(data), count);
stream.next(m.svid);
stream.next(m.how);
m.sf1d.clear();
m.sf2d.clear();
m.sf3d.clear();
if (count == 104) {
typename Msg::_sf1d_type::value_type temp1;
typename Msg::_sf2d_type::value_type temp2;
typename Msg::_sf3d_type::value_type temp3;
m.sf1d.resize(8);
for(std::size_t i = 0; i < 8; ++i) {
stream.next(temp1);
m.sf1d.push_back(temp1);
}
m.sf2d.resize(8);
for(std::size_t i = 0; i < 8; ++i) {
stream.next(temp2);
m.sf2d.push_back(temp2);
}
m.sf3d.resize(8);
for(std::size_t i = 0; i < 8; ++i) {
stream.next(temp3);
m.sf3d.push_back(temp3);
}
}
}
static uint32_t serializedLength (typename CallTraits::param_type m) {
return 8 + (4 * m.sf1d.size()) + (4 * m.sf2d.size()) + (4 * m.sf3d.size());
}
static void write(uint8_t *data, uint32_t size,
typename CallTraits::param_type m) {
ros::serialization::OStream stream(data, size);
stream.next(m.svid);
stream.next(m.how);
for(std::size_t i = 0; i < m.sf1d.size(); ++i)
ros::serialization::serialize(stream, m.sf1d[i]);
for(std::size_t i = 0; i < m.sf2d.size(); ++i)
ros::serialization::serialize(stream, m.sf2d[i]);
for(std::size_t i = 0; i < m.sf3d.size(); ++i)
ros::serialization::serialize(stream, m.sf3d[i]);
}
};
///
/// @brief Serializes the AidALM message which has a repeated block.
///
template <typename ContainerAllocator>
struct Serializer<ublox_msgs::AidALM_<ContainerAllocator> > {
typedef ublox_msgs::AidALM_<ContainerAllocator> Msg;
typedef boost::call_traits<Msg> CallTraits;
static void read(const uint8_t *data, uint32_t count,
typename CallTraits::reference m) {
ros::serialization::IStream stream(const_cast<uint8_t *>(data), count);
stream.next(m.svid);
stream.next(m.week);
m.dwrd.clear();
if (count == 40) {
typename Msg::_dwrd_type::value_type temp;
m.dwrd.resize(8);
for(std::size_t i = 0; i < 8; ++i) {
stream.next(temp);
m.dwrd.push_back(temp);
}
}
}
static uint32_t serializedLength (typename CallTraits::param_type m) {
return 8 + (4 * m.dwrd.size());
}
static void write(uint8_t *data, uint32_t size,
typename CallTraits::param_type m) {
ros::serialization::OStream stream(data, size);
stream.next(m.svid);
stream.next(m.week);
for(std::size_t i = 0; i < m.dwrd.size(); ++i)
ros::serialization::serialize(stream, m.dwrd[i]);
}
};
///
/// @brief Serializes the AidEPH message which has a repeated block.
///
template <typename ContainerAllocator>
struct Serializer<ublox_msgs::AidEPH_<ContainerAllocator> >
{
typedef ublox_msgs::AidEPH_<ContainerAllocator> Msg;
typedef boost::call_traits<Msg> CallTraits;
static void read(const uint8_t *data, uint32_t count,
typename CallTraits::reference m) {
ros::serialization::IStream stream(const_cast<uint8_t *>(data), count);
stream.next(m.svid);
stream.next(m.how);
m.sf1d.clear();
m.sf2d.clear();
m.sf3d.clear();
if (count == 104) {
typename Msg::_sf1d_type::value_type temp1;
typename Msg::_sf2d_type::value_type temp2;
typename Msg::_sf3d_type::value_type temp3;
m.sf1d.resize(8);
for(std::size_t i = 0; i < 8; ++i) {
stream.next(temp1);
m.sf1d.push_back(temp1);
}
m.sf2d.resize(8);
for(std::size_t i = 0; i < 8; ++i) {
stream.next(temp2);
m.sf2d.push_back(temp2);
}
m.sf3d.resize(8);
for(std::size_t i = 0; i < 8; ++i) {
stream.next(temp3);
m.sf3d.push_back(temp3);
}
}
}
static uint32_t serializedLength (typename CallTraits::param_type m) {
return 8 + (4 * m.sf1d.size()) + (4 * m.sf2d.size()) + (4 * m.sf3d.size());
}
static void write(uint8_t *data, uint32_t size,
typename CallTraits::param_type m) {
ros::serialization::OStream stream(data, size);
stream.next(m.svid);
stream.next(m.how);
for(std::size_t i = 0; i < m.sf1d.size(); ++i)
ros::serialization::serialize(stream, m.sf1d[i]);
for(std::size_t i = 0; i < m.sf2d.size(); ++i)
ros::serialization::serialize(stream, m.sf2d[i]);
for(std::size_t i = 0; i < m.sf3d.size(); ++i)
ros::serialization::serialize(stream, m.sf3d[i]);
}
};
///
/// @brief Serializes the EsfMEAS message which has a repeated block and an
/// optional block.
///
template <typename ContainerAllocator>
struct Serializer<ublox_msgs::EsfMEAS_<ContainerAllocator> > {
typedef boost::call_traits<ublox_msgs::EsfMEAS_<ContainerAllocator> >
CallTraits;
static void read(const uint8_t *data, uint32_t count,
typename CallTraits::reference m) {
ros::serialization::IStream stream(const_cast<uint8_t *>(data), count);
stream.next(m.timeTag);
stream.next(m.flags);
stream.next(m.id);
bool calib_valid = m.flags & m.FLAGS_CALIB_T_TAG_VALID;
int data_size = (count - (calib_valid ? 12 : 8)) / 4;
// Repeating block
m.data.resize(data_size);
for(std::size_t i = 0; i < data_size; ++i)
ros::serialization::deserialize(stream, m.data[i]);
// Optional block
if(calib_valid) {
m.calibTtag.resize(1);
ros::serialization::deserialize(stream, m.calibTtag[0]);
}
}
static uint32_t serializedLength (typename CallTraits::param_type m) {
return 4 + 8 * m.data.size() + 4 * m.calibTtag.size();
}
static void write(uint8_t *data, uint32_t size,
typename CallTraits::param_type m) {
ros::serialization::OStream stream(data, size);
stream.next(m.timeTag);
stream.next(m.flags);
stream.next(m.id);
for(std::size_t i = 0; i < m.data.size(); ++i)
ros::serialization::serialize(stream, m.data[i]);
for(std::size_t i = 0; i < m.calibTtag.size(); ++i)
ros::serialization::serialize(stream, m.calibTtag[i]);
}
};
///
/// @brief Serializes the EsfRAW message which has a repeated block.
///
template <typename ContainerAllocator>
struct Serializer<ublox_msgs::EsfRAW_<ContainerAllocator> > {
typedef boost::call_traits<ublox_msgs::EsfRAW_<ContainerAllocator> >
CallTraits;
static void read(const uint8_t *data, uint32_t count,
typename CallTraits::reference m) {
ros::serialization::IStream stream(const_cast<uint8_t *>(data), count);
stream.next(m.reserved0);
m.blocks.clear();
int num_blocks = (count - 4) / 8;
m.blocks.resize(num_blocks);
for(std::size_t i = 0; i < num_blocks; ++i)
ros::serialization::deserialize(stream, m.blocks[i]);
}
static uint32_t serializedLength (typename CallTraits::param_type m) {
return 4 + 8 * m.blocks.size();
}
static void write(uint8_t *data, uint32_t size,
typename CallTraits::param_type m) {
ros::serialization::OStream stream(data, size);
stream.next(m.reserved0);
for(std::size_t i = 0; i < m.blocks.size(); ++i)
ros::serialization::serialize(stream, m.blocks[i]);
}
};
///
/// @brief Serializes the EsfSTATUS message which has a repeated block.
///
template <typename ContainerAllocator>
struct Serializer<ublox_msgs::EsfSTATUS_<ContainerAllocator> > {
typedef ublox_msgs::EsfSTATUS_<ContainerAllocator> Msg;
typedef boost::call_traits<Msg> CallTraits;
static void read(const uint8_t *data, uint32_t count,
typename CallTraits::reference m) {
ros::serialization::IStream stream(const_cast<uint8_t *>(data), count);
stream.next(m.iTOW);
stream.next(m.version);
stream.next(m.fusionMode);
stream.next(m.reserved2);
stream.next(m.numSens);
m.sens.resize(m.numSens);
for(std::size_t i = 0; i < m.sens.size(); ++i)
ros::serialization::deserialize(stream, m.sens[i]);
}
static uint32_t serializedLength (typename CallTraits::param_type m) {
return 16 + 4 * m.numSens;
}
static void write(uint8_t *data, uint32_t size,
typename CallTraits::param_type m) {
if(m.sens.size() != m.numSens) {
ROS_ERROR("Writing EsfSTATUS message: numSens must equal size of sens");
}
ros::serialization::OStream stream(data, size);
stream.next(m.iTOW);
stream.next(m.version);
stream.next(m.fusionMode);
stream.next(m.reserved2);
stream.next(static_cast<typename Msg::_numSens_type>(m.sens.size()));
for(std::size_t i = 0; i < m.sens.size(); ++i)
ros::serialization::serialize(stream, m.sens[i]);
}
};
} // namespace ublox
#endif // UBLOX_SERIALIZATION_UBLOX_MSGS_H

View File

@@ -0,0 +1,251 @@
//==============================================================================
// Copyright (c) 2012, Johannes Meyer, TU Darmstadt
// All rights reserved.
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of the Flight Systems and Automatic Control group,
// TU Darmstadt, nor the names of its contributors may be used to
// endorse or promote products derived from this software without
// specific prior written permission.
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//==============================================================================
#ifndef UBLOX_MSGS_H
#define UBLOX_MSGS_H
#include <ublox_msgs/NavATT.h>
#include <ublox_msgs/NavCLOCK.h>
#include <ublox_msgs/NavDGPS.h>
#include <ublox_msgs/NavDOP.h>
#include <ublox_msgs/NavPOSECEF.h>
#include <ublox_msgs/NavPOSLLH.h>
#include <ublox_msgs/NavRELPOSNED.h>
#include <ublox_msgs/NavSBAS.h>
#include <ublox_msgs/NavSOL.h>
#include <ublox_msgs/NavPVT.h>
#include <ublox_msgs/NavPVT7.h>
#include <ublox_msgs/NavSTATUS.h>
#include <ublox_msgs/NavSAT.h>
#include <ublox_msgs/NavSVIN.h>
#include <ublox_msgs/NavSVINFO.h>
#include <ublox_msgs/NavTIMEGPS.h>
#include <ublox_msgs/NavTIMEUTC.h>
#include <ublox_msgs/NavVELECEF.h>
#include <ublox_msgs/NavVELNED.h>
#include <ublox_msgs/RxmALM.h>
#include <ublox_msgs/RxmEPH.h>
#include <ublox_msgs/RxmRAW.h>
#include <ublox_msgs/RxmRAW_SV.h>
#include <ublox_msgs/RxmRAWX.h>
#include <ublox_msgs/RxmRAWX_Meas.h>
#include <ublox_msgs/RxmRTCM.h>
#include <ublox_msgs/RxmSFRB.h>
#include <ublox_msgs/RxmSFRBX.h>
#include <ublox_msgs/RxmSVSI.h>
#include <ublox_msgs/Inf.h>
#include <ublox_msgs/Ack.h>
#include <ublox_msgs/CfgANT.h>
#include <ublox_msgs/CfgCFG.h>
#include <ublox_msgs/CfgDAT.h>
#include <ublox_msgs/CfgDGNSS.h>
#include <ublox_msgs/CfgGNSS.h>
#include <ublox_msgs/CfgHNR.h>
#include <ublox_msgs/CfgINF.h>
#include <ublox_msgs/CfgINF_Block.h>
#include <ublox_msgs/CfgMSG.h>
#include <ublox_msgs/CfgNAV5.h>
#include <ublox_msgs/CfgNAVX5.h>
#include <ublox_msgs/CfgNMEA.h>
#include <ublox_msgs/CfgNMEA6.h>
#include <ublox_msgs/CfgNMEA7.h>
#include <ublox_msgs/CfgPRT.h>
#include <ublox_msgs/CfgRATE.h>
#include <ublox_msgs/CfgRST.h>
#include <ublox_msgs/CfgSBAS.h>
#include <ublox_msgs/CfgTMODE3.h>
#include <ublox_msgs/CfgUSB.h>
#include <ublox_msgs/UpdSOS.h>
#include <ublox_msgs/UpdSOS_Ack.h>
#include <ublox_msgs/MonGNSS.h>
#include <ublox_msgs/MonHW.h>
#include <ublox_msgs/MonHW6.h>
#include <ublox_msgs/MonVER.h>
#include <ublox_msgs/AidALM.h>
#include <ublox_msgs/AidEPH.h>
#include <ublox_msgs/AidHUI.h>
#include <ublox_msgs/EsfINS.h>
#include <ublox_msgs/EsfMEAS.h>
#include <ublox_msgs/EsfRAW.h>
#include <ublox_msgs/EsfSTATUS.h>
#include <ublox_msgs/EsfSTATUS_Sens.h>
#include <ublox_msgs/MgaGAL.h>
#include <ublox_msgs/HnrPVT.h>
namespace ublox_msgs {
namespace Class {
static const uint8_t NAV = 0x01; //!< Navigation Result Messages: Position,
//!< Speed, Time, Acceleration, Heading,
//!< DOP, SVs used
static const uint8_t RXM = 0x02; //!< Receiver Manager Messages:
//!< Satellite Status, RTC Status
static const uint8_t INF = 0x04; //!< Information Messages:
//!< Printf-Style Messages, with IDs such as
//!< Error, Warning, Notice
static const uint8_t ACK = 0x05; //!< Ack/Nack Messages: Acknowledge or Reject
//!< messages to CFG input messages
static const uint8_t CFG = 0x06; //!< Configuration Input Messages: Set
//!< Dynamic Model, Set DOP Mask, Set Baud
//!< Rate, etc.
static const uint8_t UPD = 0x09; //!< Firmware Update Messages: i.e.
//!< Memory/Flash erase/write, Reboot, Flash
//!< identification, etc.
//!< Used to update the firmware and identify
//!< any attached flash device
static const uint8_t MON = 0x0A; //!< Monitoring Messages: Communication
//!< Status, CPU Load, Stack Usage,
//!< Task Status
static const uint8_t AID = 0x0B; //!< AssistNow Aiding Messages: Ephemeris,
//!< Almanac, other A-GPS data input
static const uint8_t TIM = 0x0D; //!< Timing Messages: Timepulse Output,
//!< Timemark Results
static const uint8_t ESF = 0x10; //!< External Sensor Fusion Messages:
//!< External sensor measurements and status
//!< information
static const uint8_t MGA = 0x13; //!< Multiple GNSS Assistance Messages:
//!< Assistance data for various GNSS
static const uint8_t LOG = 0x21; //!< Logging Messages: Log creation,
//!< deletion, info and retrieval
static const uint8_t SEC = 0x27; //!< Security Feature Messages
static const uint8_t HNR = 0x28; //!< High Rate Navigation Results Messages:
//!< High rate time, position, speed, heading
static const uint8_t RTCM = 0xF5; //!< RTCM Configuration Messages
}
namespace Message {
namespace NAV {
static const uint8_t ATT = NavATT::MESSAGE_ID;
static const uint8_t CLOCK = NavCLOCK::MESSAGE_ID;
static const uint8_t DGPS = NavDGPS::MESSAGE_ID;
static const uint8_t DOP = NavDOP::MESSAGE_ID;
static const uint8_t POSECEF = NavPOSECEF::MESSAGE_ID;
static const uint8_t POSLLH = NavPOSLLH::MESSAGE_ID;
static const uint8_t RELPOSNED = NavRELPOSNED::MESSAGE_ID;
static const uint8_t SBAS = NavSBAS::MESSAGE_ID;
static const uint8_t SOL = NavSOL::MESSAGE_ID;
static const uint8_t PVT = NavPVT::MESSAGE_ID;
static const uint8_t SAT = NavSAT::MESSAGE_ID;
static const uint8_t STATUS = NavSTATUS::MESSAGE_ID;
static const uint8_t SVINFO = NavSVINFO::MESSAGE_ID;
static const uint8_t SVIN = NavSVIN::MESSAGE_ID;
static const uint8_t TIMEGPS = NavTIMEGPS::MESSAGE_ID;
static const uint8_t TIMEUTC = NavTIMEUTC::MESSAGE_ID;
static const uint8_t VELECEF = NavVELECEF::MESSAGE_ID;
static const uint8_t VELNED = NavVELNED::MESSAGE_ID;
}
namespace RXM {
static const uint8_t ALM = RxmALM::MESSAGE_ID;
static const uint8_t EPH = RxmEPH::MESSAGE_ID;
static const uint8_t RAW = RxmRAW::MESSAGE_ID;
static const uint8_t RAWX = RxmRAWX::MESSAGE_ID;
static const uint8_t RTCM = RxmRTCM::MESSAGE_ID;
static const uint8_t SFRB = RxmSFRB::MESSAGE_ID;
static const uint8_t SFRBX = RxmSFRBX::MESSAGE_ID;
static const uint8_t SVSI = RxmSVSI::MESSAGE_ID;
}
namespace INF {
static const uint8_t ERROR = 0x00;
static const uint8_t WARNING = 0x01;
static const uint8_t NOTICE = 0x02;
static const uint8_t TEST = 0x03;
static const uint8_t DEBUG = 0x04;
}
namespace ACK {
static const uint8_t NACK = 0x00;
static const uint8_t ACK = 0x01;
}
namespace AID {
static const uint8_t ALM = AidALM::MESSAGE_ID;
static const uint8_t EPH = AidEPH::MESSAGE_ID;
static const uint8_t HUI = AidHUI::MESSAGE_ID;
}
namespace CFG {
static const uint8_t ANT = CfgANT::MESSAGE_ID;
static const uint8_t CFG = CfgCFG::MESSAGE_ID;
static const uint8_t DAT = CfgDAT::MESSAGE_ID;
static const uint8_t GNSS = CfgGNSS::MESSAGE_ID;
static const uint8_t HNR = CfgHNR::MESSAGE_ID;
static const uint8_t INF = CfgINF::MESSAGE_ID;
static const uint8_t DGNSS = CfgDGNSS::MESSAGE_ID;
static const uint8_t MSG = CfgMSG::MESSAGE_ID;
static const uint8_t NAV5 = CfgNAV5::MESSAGE_ID;
static const uint8_t NAVX5 = CfgNAVX5::MESSAGE_ID;
static const uint8_t NMEA = CfgNMEA::MESSAGE_ID;
static const uint8_t PRT = CfgPRT::MESSAGE_ID;
static const uint8_t RATE = CfgRATE::MESSAGE_ID;
static const uint8_t RST = CfgRST::MESSAGE_ID;
static const uint8_t SBAS = CfgSBAS::MESSAGE_ID;
static const uint8_t TMODE3 = CfgTMODE3::MESSAGE_ID;
static const uint8_t USB = CfgUSB::MESSAGE_ID;
}
namespace UPD {
//! SOS and SOS_Ack have the same message ID, but different lengths
static const uint8_t SOS = UpdSOS::MESSAGE_ID;
}
namespace MON {
static const uint8_t GNSS = MonGNSS::MESSAGE_ID;
static const uint8_t HW = MonHW::MESSAGE_ID;
static const uint8_t VER = MonVER::MESSAGE_ID;
}
namespace ESF {
static const uint8_t INS = EsfINS::MESSAGE_ID;
static const uint8_t MEAS = EsfMEAS::MESSAGE_ID;
static const uint8_t RAW = EsfRAW::MESSAGE_ID;
static const uint8_t STATUS = EsfSTATUS::MESSAGE_ID;
}
namespace MGA {
static const uint8_t GAL = MgaGAL::MESSAGE_ID;
}
namespace HNR {
static const uint8_t PVT = HnrPVT::MESSAGE_ID;
}
}
} //!< namespace ublox_msgs
#endif //!< UBLOX_MSGS_H

View File

@@ -0,0 +1,12 @@
# ACK (0x05)
# Message Acknowledged / Not-Acknowledged
#
# Output upon processing of an input message
#
uint8 CLASS_ID = 5
uint8 NACK_MESSAGE_ID = 0
uint8 ACK_MESSAGE_ID = 1
uint8 clsID # Class ID of the (Not-)Acknowledged Message
uint8 msgID # Message ID of the (Not-)Acknowledged Message

View File

@@ -0,0 +1,28 @@
# AID-ALM (0x0B 0x30)
# GPS Aiding Almanach Input/Output Message
#
# All UBX-AID messages are deprecated; use UBX-MGA messages instead
# - If the WEEK Value is 0, DWRD0 to DWRD7 are not sent as the almanach is not
# available for the given SV. This may happen even if NAV-SVINFO and RXM-SVSI
# are indicating almanac availability as the internal data may not represent
# the content of an original broadcast almanac (or only parts thereof).
# - DWORD0 to DWORD7 contain the 8 words following the Hand-Over Word ( HOW )
# from the GPS navigation message, either pages 1 to 24 of sub-frame 5 or
# pages 2 to 10 of subframe 4. See IS-GPS-200 for a full description of the
# contents of the Almanac pages.
# - In DWORD0 to DWORD7, the parity bits have been removed, and the 24 bits of
# data are located in Bits 0 to 23. Bits 24 to 31 shall be ignored.
# - Example: Parameter e (Eccentricity) from Almanach Subframe 4/5, Word 3,
# Bits 69-84 within the subframe can be found in DWRD0, Bits 15-0 whereas
# Bit 0 is the LSB.
uint8 CLASS_ID = 11
uint8 MESSAGE_ID = 48
uint32 svid # SV ID for which the receiver shall return its
# Almanac Data (Valid Range: 1 .. 32 or 51, 56, 63).
uint32 week # Issue Date of Almanach (GPS week number)
# Start of optional block
uint32[] dwrd # Almanach Words
# End of optional block

View File

@@ -0,0 +1,33 @@
# AID-EPH (0x0B 0x31)
# GPS Aiding Ephemeris Input/Output Message
#
# All UBX-AID messages are deprecated; use UBX-MGA messages instead
# - SF1D0 to SF3D7 is only sent if ephemeris is available for this SV. If not, the payload may
# be reduced to 8 Bytes, or all bytes are set to zero, indicating that this SV Number does
# not have valid ephemeris for the moment. This may happen even if NAV-SVINFO and
# RXM-SVSI are indicating ephemeris availability as the internal data may not represent the
# content of an original broadcast ephemeris (or only parts thereof).
# - SF1D0 to SF3D7 contain the 24 words following the Hand-Over Word ( HOW ) from the
# GPS navigation message, subframes 1 to 3. The Truncated TOW Count is not valid and
# cannot be used. See IS-GPS-200 for a full description of the contents of the Subframes.
# - In SF1D0 to SF3D7, the parity bits have been removed, and the 24 bits of data are
# located in Bits 0 to 23. Bits 24 to 31 shall be ignored.
# - When polled, the data contained in this message does not represent the full original
# ephemeris broadcast. Some fields that are irrelevant to u-blox receivers may be missing.
# The week number in Subframe 1 has already been modified to match the Time Of
# Ephemeris (TOE).
uint8 CLASS_ID = 11
uint8 MESSAGE_ID = 49
uint32 svid # SV ID for which this ephemeris data is
# (Valid Range: 1 .. 32).
uint32 how # Hand-Over Word of first Subframe. This is
# required if data is sent to the receiver.
# 0 indicates that no Ephemeris Data is following.
# Start of optional block
uint32[] sf1d # Subframe 1 Words 3..10 (SF1D0..SF1D7)
uint32[] sf2d # Subframe 2 Words 3..10 (SF2D0..SF2D7)
uint32[] sf3d # Subframe 3 Words 3..10 (SF3D0..SF3D7)
# End of optional block

View File

@@ -0,0 +1,35 @@
# AID-HUI (0x0B 0x02)
# GPS Health, UTC and ionosphere parameters
#
# All UBX-AID messages are deprecated; use UBX-MGA messages instead.
# This message contains a health bit mask, UTC time and Klobuchar parameters. For more
# information on these parameters, please see the ICD-GPS-200 documentation.
uint8 CLASS_ID = 11
uint8 MESSAGE_ID = 2
uint32 health # Bitmask, every bit represents a GPS SV (1-32).
# If the bit is set the SV is healthy.
float64 utcA0 # UTC - parameter A0
float64 utcA1 # UTC - parameter A1
int32 utcTOW # UTC - reference time of week
int16 utcWNT # UTC - reference week number
int16 utcLS # UTC - time difference due to leap seconds before event
int16 utcWNF # UTC - week number when next leap second event occurs
int16 utcDN # UTC - day of week when next leap second event occurs
int16 utcLSF # UTC - time difference due to leap seconds after event
int16 utcSpare # UTC - Spare to ensure structure is a multiple of 4
# bytes
float32 klobA0 # Klobuchar - alpha 0 [s]
float32 klobA1 # Klobuchar - alpha 1 [s/semicircle]
float32 klobA2 # Klobuchar - alpha 2 [s/semicircle^2]
float32 klobA3 # Klobuchar - alpha 3 [s/semicircle^3]
float32 klobB0 # Klobuchar - beta 0 [s]
float32 klobB1 # Klobuchar - beta 1 [s/semicircle]
float32 klobB2 # Klobuchar - beta 2 [s/semicircle^2]
float32 klobB3 # Klobuchar - beta 3 [s/semicircle^3]
uint32 flags # flags
uint32 FLAGS_HEALTH = 1 # Healthmask field in this message is valid
uint32 FLAGS_UTC = 2 # UTC parameter fields in this message are valid
uint32 FLAGS_KLOB = 4 # Klobuchar parameter fields in this message are
# valid

View File

@@ -0,0 +1,25 @@
# CFG-ANT (0x06 0x13)
# Antenna Control Settings
#
uint8 CLASS_ID = 6
uint8 MESSAGE_ID = 19
uint16 flags # Antenna Flag Mask
uint16 FLAGS_SVCS = 1 # Enable Antenna Supply Voltage Control Signal
uint16 FLAGS_SCD = 2 # Enable Short Circuit Detection
uint16 FLAGS_OCD = 4 # Enable Open Circuit Detection
uint16 FLAGS_PDWN_ON_SCD = 8 # Power Down Antenna supply if Short Circuit is
# detected. (only in combination with Bit 1)
uint16 FLAGS_RECOVERY = 16 # Enable automatic recovery from short state
uint16 pins # Antenna Pin Configuration
uint16 PIN_SWITCH_MASK = 31 # PIO-Pin used for switching antenna supply
# (internal to TIM-LP/TIM-LF)
uint16 PIN_SCD_MASK = 992 # PIO-Pin used for detecting a short in the
# antenna supply
uint16 PIN_OCD_MASK = 31744 # PIO-Pin used for detecting open/not connected
# antenna
uint16 PIN_RECONFIG = 32678 # if set to one, and this command is sent to the
# receiver, the receiver will reconfigure the
# pins as specified.

View File

@@ -0,0 +1,38 @@
# CFG-CFG (0x06 0x09)
# Clear, Save and Load configurations
#
uint8 CLASS_ID = 6
uint8 MESSAGE_ID = 9
uint32 clearMask # Mask with configuration sub-sections to Clear
# (=Load Default Configurations to Permanent
# Configurations in non-volatile memory)
uint32 saveMask # Mask with configuration sub-section to Save
# (=Save Current Configuration to Non-volatile
# Memory)
uint32 loadMask # Mask with configuration sub-sections to Load
# (=Load Permanent Configurations from
# Non-volatile Memory to Current Configurations)
uint32 MASK_IO_PORT = 1 # Communications port settings. Modifying this
# sub-section results in an IO system reset.
# Because of this undefined data may be output
# for a short period of time after receiving the
# message.
uint32 MASK_MSG_CONF = 2 # Message Configuration
uint32 MASK_INF_MSG = 4 # INF Message Configuration
uint32 MASK_NAV_CONF = 8 # Navigation Configuration
uint32 MASK_RXM_CONF = 16 # Receiver Manager Configuration
uint32 MASK_SEN_CONF = 256 # Sensor Interface Configuration, protocol >= 19
uint32 MASK_RINV_CONF = 512 # Remote Inventory Configuration
uint32 MASK_ANT_CONF = 1024 # Antenna Configuration
uint32 MASK_LOG_CONF = 2048 # Logging Configuration
uint32 MASK_FTS_CONF = 4096 # FTS Configuration. Only applicable to the
# FTS product variant.
uint8 deviceMask # Mask which selects the devices for this command
uint8 DEV_BBR = 1 # device battery backed RAM
uint8 DEV_FLASH = 2 # device Flash
uint8 DEV_EEPROM = 4 # device EEPROM
uint8 DEV_SPI_FLASH = 16 # device SPI Flash

View File

@@ -0,0 +1,37 @@
# CFG-DAT (0x06 0x06)
# Set User-defined Datum
#
# For more information see the description of Geodetic Systems and Frames.
#
uint8 CLASS_ID = 6
uint8 MESSAGE_ID = 6
# Only for GET, these values are not used for write
uint16 datumNum # Datum Number: 0 = WGS84, 0xFFFF = user-defined
uint16 DATUM_NUM_WGS84 = 0
uint16 DATUM_NUM_USER = 65535
uint8[6] datumName # ASCII String: WGS84 or USER
float64 majA # Semi-major Axis [m]
# accepted range = 6,300,000.0 to 6,500,000.0 meters
float64 flat # 1.0 / Flattening
# accepted range is 0.0 to 500.0
float32 dX # X Axis shift at the origin [m]
# accepted range is +/- 5000.0 meters
float32 dY # Y Axis shift at the origin [m]
# accepted range is +/- 5000.0 meters
float32 dZ # Z Axis shift at the origin [m]
# accepted range is +/- 5000.0 meters
float32 rotX # Rotation about the X Axis [s]
# accepted range is +/- 20.0 milli-arc seconds
float32 rotY # Rotation about the Y Axis [s]
# accepted range is +/- 20.0 milli-arc seconds
float32 rotZ # Rotation about the Z Axis [s]
# accepted range is +/- 20.0 milli-arc seconds
float32 scale # Scale change [ppm]
# accepted range is 0.0 to 50.0 parts per million

View File

@@ -0,0 +1,18 @@
# CFG-DGNSS (0x06 0x70)
# DGNSS configuration
#
# This message allows the user to configure the DGNSS configuration of the
# receiver.
# Supported on:
# - u-blox 8 / u-blox M8 from protocol version 20.01 up to version 23.01 (only
# with High Precision GNSS products)
uint8 CLASS_ID = 6
uint8 MESSAGE_ID = 112
uint8 dgnssMode # Specifies differential mode:
uint8 DGNSS_MODE_RTK_FLOAT = 2 # RTK float: No attempts are made to fix
# ambiguities.
uint8 DGNSS_MODE_RTK_FIXED = 3 # RTK fixed: Ambiguities are fixed whenever
# possible.
uint8[3] reserved0 # Reserved

View File

@@ -0,0 +1,44 @@
# CFG-GNSS (0x06 0x3E)
# GNSS Configuration
#
# Gets or sets the GNSS system channel sharing configuration.
# If the receiver is sent a valid new configuration, it will respond with a
# UBX-ACK-ACK message and immediately change to the new configuration. Otherwise
# the receiver will reject the request, by issuing a UBX-ACK-NAK and continuing
# operation with the previous configuration.
# Configuration requirements:
# - It is necessary for at least one major GNSS to be enabled, after applying
# the new configuration to the current one.
# - It is also required that at least 4 tracking channels are available to each
# enabled major GNSS, i.e. maxTrkCh must have a minimum value of 4 for each
# enabled major GNSS.
# - The number of tracking channels in use must not exceed the number of
# tracking channels available in hardware, and the sum of all reserved
# tracking channels needs to be less than or equal to the number of tracking
# channels in use.
# Notes:
# - To avoid cross-correlation issues, it is recommended that GPS and QZSS are
# always both enabled or both disabled.
# - Polling this message returns the configuration of all supported GNSS,
# whether enabled or not; it may also include GNSS unsupported by the
# particular product, but in such cases the enable flag will always be unset.
# - See section GNSS Configuration for a discussion of the use of this message
# and section Satellite Numbering for a description of the GNSS IDs available
# - Configuration specific to the GNSS system can be done via other messages
# (e.g. UBX-CFG-SBAS).
#
uint8 CLASS_ID = 6
uint8 MESSAGE_ID = 62
uint8 msgVer # Message version (= 0 for this version)
uint8 numTrkChHw # Number of tracking channels in hardware (read only)
uint8 numTrkChUse # (Read only in protocol versions greater than 23)
# Number of tracking channels to use (<= numTrkChHw)
# If 0xFF, then number of tracking channels to use will
# be set to numTrkChHw
uint8 numConfigBlocks # Number of configuration blocks following
# Start of repeated block (numConfigBlocks times)
CfgGNSS_Block[] blocks
# End of repeated block

View File

@@ -0,0 +1,54 @@
# see Cfg-GNSS message
#
uint8 gnssId # System identifier (see Satellite Numbering)
uint8 GNSS_ID_GPS = 0
uint8 GNSS_ID_SBAS = 1
uint8 GNSS_ID_GALILEO = 2
uint8 GNSS_ID_BEIDOU = 3
uint8 GNSS_ID_IMES = 4
uint8 GNSS_ID_QZSS = 5
uint8 GNSS_ID_GLONASS = 6
uint8 resTrkCh # (Read only in protocol versions greater than 23)
# Number of reserved (minimum) tracking channels
# for this GNSS system
uint8 RES_TRK_CH_GPS = 8
uint8 RES_TRK_CH_QZSS = 0
uint8 RES_TRK_CH_SBAS = 0
uint8 RES_TRK_CH_GLONASS = 8
uint8 maxTrkCh # (Read only in protocol versions greater than 23)
# Maximum number of tracking channels used for this
# system. Must be > 0, >= resTrkChn, <= numTrkChUse and
# <= maximum number of tracking channels supported for
# this system
uint8 MAX_TRK_CH_MAJOR_MIN = 4 # maxTrkCh must have this minimum value
# for each enabled major GNSS
uint8 MAX_TRK_CH_GPS = 16
uint8 MAX_TRK_CH_GLONASS = 14
uint8 MAX_TRK_CH_QZSS = 3
uint8 MAX_TRK_CH_SBAS = 3
uint8 reserved1 # Reserved
uint32 flags # Bitfield of flags. At least one signal must be
# configured in every enabled system.
uint32 FLAGS_ENABLE = 1 # Enable this system
uint32 FLAGS_SIG_CFG_MASK = 16711680 # Signal configuration mask
uint32 SIG_CFG_GPS_L1CA = 65536 # When gnssId is 0 (GPS)
# * 0x01 = GPS L1C/A
uint32 SIG_CFG_SBAS_L1CA = 65536 # When gnssId is 1 (SBAS)
# * 0x01 = SBAS L1C/A
uint32 SIG_CFG_GALILEO_E1OS = 65536 # When gnssId is 2 (Galileo)
# * 0x01 = Galileo E1OS (not supported in
# protocol versions less than 18)
uint32 SIG_CFG_BEIDOU_B1I = 65536 # When gnssId is 3 (BeiDou)
# * 0x01 = BeiDou B1I
uint32 SIG_CFG_IMES_L1 = 65536 # When gnssId is 4 (IMES)
# * 0x01 = IMES L1
uint32 SIG_CFG_QZSS_L1CA = 65536 # When gnssId is 5 (QZSS)
# * 0x01 = QZSS L1C/A
uint32 SIG_CFG_QZSS_L1SAIF = 262144 # * 0x04 = QZSS L1SAIF
uint32 SIG_CFG_GLONASS_L1OF = 65536 # When gnssId is 6 (GLONASS)
# * 0x01 = GLONASS L1OF

View File

@@ -0,0 +1,19 @@
# CFG-HNR (0x06 0x5C)
# High Navigation Rate Settings
#
# The u-blox receivers support high rates of navigation update up to 30 Hz.
# The navigation solution output (NAV-HNR) will not be aligned to the top of a
# second.
# The update rate has a direct influence on the power consumption. The more
# fixes that are required, the more CPU power and communication resources are
# required.
# For most applications a 1 Hz update rate would be sufficient.
#
# (only with ADR or UDR products)
#
uint8 CLASS_ID = 6
uint8 MESSAGE_ID = 92
uint8 highNavRate # Rate of navigation solution output [Hz]
uint8[3] reserved0 # Reserved

View File

@@ -0,0 +1,19 @@
# CFG-INF (0x06 0x02)
# Information message configuration
#
# The value of infMsgMask[x] below are that each bit represents one of the INF
# class messages (Bit 0 for ERROR, Bit 1 for WARNING and so on.). For a complete
# list, see the Message Class INF. Several configurations can be concatenated to
# one input message.
# In this case the payload length can be a multiple of the normal length. Output
# messages from the module contain only one configuration unit. Note that I/O
# Ports 1 and 2 correspond to serial ports 1 and 2. I/O port 0 is DDC. I/O port
# 3 is USB. I/O port 4 is SPI. I/O port 5 is reserved for future use
#
uint8 CLASS_ID = 6
uint8 MESSAGE_ID = 2
# start of repeated block
CfgINF_Block[] blocks
# end of repeated block

View File

@@ -0,0 +1,21 @@
# See CfgINF message
#
uint8 protocolID # Protocol Identifier, identifying for which
# protocol the configuration is set/get. The
# following are valid Protocol Identifiers:
# 0: UBX Protocol
# 1: NMEA Protocol
# 2-255: Reserved
uint8 PROTOCOL_ID_UBX = 0
uint8 PROTOCOL_ID_NMEA = 1
uint8[3] reserved1 # Reserved
uint8[6] infMsgMask # A bit mask, saying which information messages
# are enabled on each I/O port
uint8 INF_MSG_ERROR = 1 # enable ERROR
uint8 INF_MSG_WARNING = 2 # enable WARNING
uint8 INF_MSG_NOTICE = 4 # enable NOTICE
uint8 INF_MSG_TEST = 8 # enable TEST
uint8 INF_MSG_DEBUG = 16 # enable DEBUG

View File

@@ -0,0 +1,12 @@
# CFG-MSG (0x06 0x01)
# Message Rate(s)
#
# Set message rate for the current port
uint8 CLASS_ID = 6
uint8 MESSAGE_ID = 1
uint8 msgClass # Message Class
uint8 msgID # Message Identifier
uint8 rate # Send rate on current port
# [number of navigation solutions]

View File

@@ -0,0 +1,66 @@
# CFG-NAV5 (0x06 0x24)
# Navigation Engine Settings
uint8 CLASS_ID = 6
uint8 MESSAGE_ID = 36
uint16 mask # Parameters Bitmask. Only the masked
# parameters will be applied.
uint16 MASK_DYN = 1 # Apply dynamic model settings
uint16 MASK_MIN_EL = 2 # Apply minimum elevation settings
uint16 MASK_FIX_MODE = 4 # Apply fix mode settings
uint16 MASK_DR_LIM = 8 # Apply DR limit settings
uint16 MASK_POS_MASK = 16 # Apply position mask settings
uint16 MASK_TIME_MASK = 32 # Apply time mask settings
uint16 MASK_STATIC_HOLD_MASK = 64 # Apply static hold settings
uint16 MASK_DGPS_MASK = 128 # Apply DGPS settings, firmware >= 7 only
uint16 MASK_CNO = 256 # Apply CNO threshold settings
uint16 MASK_UTC = 1024 # Apply UTC settings, protocol >= 16 only
uint8 dynModel # Dynamic Platform model:
uint8 DYN_MODEL_PORTABLE = 0 # Portable
uint8 DYN_MODEL_STATIONARY = 2 # Stationary
uint8 DYN_MODEL_PEDESTRIAN = 3 # Pedestrian
uint8 DYN_MODEL_AUTOMOTIVE = 4 # Automotive
uint8 DYN_MODEL_SEA = 5 # Sea
uint8 DYN_MODEL_AIRBORNE_1G = 6 # Airborne with <1g Acceleration
uint8 DYN_MODEL_AIRBORNE_2G = 7 # Airborne with <2g Acceleration
uint8 DYN_MODEL_AIRBORNE_4G = 8 # Airborne with <4g Acceleration
uint8 DYN_MODEL_WRIST_WATCH = 9 # Wrist watch, protocol >= 18
uint8 fixMode # Position Fixing Mode.
uint8 FIX_MODE_2D_ONLY = 1 # 2D only
uint8 FIX_MODE_3D_ONLY = 2 # 3D only
uint8 FIX_MODE_AUTO = 3 # Auto 2D/3D
int32 fixedAlt # Fixed altitude (mean sea level) for 2D fix mode.
# [m / 0.01]
uint32 fixedAltVar # Fixed altitude variance for 2D mode. [m^2 / 0.0001]
int8 minElev # Minimum Elevation for a GNSS satellite to be used in
# NAV [deg]
uint8 drLimit # Maximum time to perform dead reckoning [s]
# (linear extrapolation) in case of GPS signal loss
uint16 pDop # Position DOP Mask to use [1 / 0.1]
uint16 tDop # Time DOP Mask to use [1 / 0.1]
uint16 pAcc # Position Accuracy Mask [m]
uint16 tAcc # Time Accuracy Mask [m]
uint8 staticHoldThresh # Static hold threshold [cm/s]
uint8 dgnssTimeOut # DGNSS timeout, firmware 7 and newer only [s]
uint8 cnoThreshNumSvs # Number of satellites required to have C/N0 above
# cnoThresh for a fix to be attempted
uint8 cnoThresh # C/N0 threshold for deciding whether to attempt a fix
# [dBHz]
uint8[2] reserved1 # Reserved
uint16 staticHoldMaxDist # Static hold distance threshold (before quitting
# static hold) [m]
uint8 utcStandard # UTC standard to be used:
uint8 UTC_STANDARD_AUTOMATIC = 0 # receiver selects based on GNSS configuration
uint8 UTC_STANDARD_GPS = 3 # UTC as operated by the U.S. Naval Observatory
# (USNO); derived from GPS time
uint8 UTC_STANDARD_GLONASS = 6 # UTC as operated by the former Soviet Union;
# derived from GLONASS time
uint8 UTC_STANDARD_BEIDOU = 7 # UTC as operated by the National Time Service
# Center, China; derived from BeiDou time
uint8[5] reserved2 # Reserved

View File

@@ -0,0 +1,67 @@
# CFG-NAVX5 (0x06 0x23)
# Navigation Engine Expert Settings
#
# Warning: Refer to u-blox protocol spec before changing these settings.
uint8 CLASS_ID = 6
uint8 MESSAGE_ID = 35
uint16 version # Message version (set to 0)
uint16 mask1 # First parameters bitmask (possible values below)
uint16 MASK1_MIN_MAX = 4 # apply min/max SVs settings
uint16 MASK1_MIN_CNO = 8 # apply minimum C/N0 setting
uint16 MASK1_INITIAL_FIX_3D = 64 # apply initial 3D fix settings
uint16 MASK1_WKN_ROLL = 512 # apply GPS week number rollover settings
uint16 MASK1_ACK_AID = 1024 # apply assistance acknowledgment
# settings
uint16 MASK1_PPP = 8192 # apply usePPP flag
uint16 MASK1_AOP = 16384 # apply aopCfg (useAOP flag) and
# aopOrbMaxErr settings
# (AssistNow Autonomous)
uint32 mask2 # Second parameters bitmask (possible values below)
# Firmware >=8 only
uint32 MASK2_ADR = 64 # Apply ADR sensor fusion on/off
# setting
uint32 MASK2_SIG_ATTEN_COMP_MODE = 128 # Apply signal attenuation
# compensation feature settings
uint8[2] reserved1 # Always set to zero
uint8 minSVs # Minimum number of satellites for navigation
uint8 maxSVs # Maximum number of satellites for navigation
uint8 minCNO # Minimum satellite signal level for navigation [dBHz]
uint8 reserved2 # Always set to zero
uint8 iniFix3D # If set to 1, initial fix must be 3D
uint8[2] reserved3 # Always set to zero
uint8 ackAiding # If set to 1, issue acknowledgments for assistance
uint16 wknRollover # GPS week rollover number, GPS week numbers will be set
# correctly from this week up to 1024 weeks after this
# week
uint8 sigAttenCompMode # Permanently attenuated signal compensation [dBHz]
# 0 = disabled, 255 = automatic
# 1..63 = maximum expected C/N0 value
# Firmware 8 only
uint8[5] reserved4 # Always set to zero
uint8 usePPP # Enable/disable PPP (on supported units)
uint8 aopCfg # AssistNow Autonomous configuration, 1: enabled
uint8[2] reserved5 # Always set to zero
uint16 aopOrbMaxErr # Maximum acceptable (modeled) autonomous orbit
# error [m]
# valid range = 5..1000
# 0 = reset to firmware default
uint8[7] reserved6 # Always set to zero
uint8 useAdr # Enable/disable ADR sensor fusion
# 1: enabled, 0: disabled
# Only supported on certain products

View File

@@ -0,0 +1,85 @@
# CFG-NMEA (0x06 0x17)
# NMEA protocol configuration V1
#
# Set/Get the NMEA protocol configuration. See section NMEA Protocol
# Configuration for a detailed description of the configuration effects on
# NMEA output
#
uint8 CLASS_ID = 6
uint8 MESSAGE_ID = 23
uint8 filter # filter flags
uint8 FILTER_POS = 1 # Enable position output for failed or
# invalid fixes
uint8 FILTER_MSK_POS = 2 # Enable position output for invalid fixes
uint8 FILTER_TIME = 4 # Enable time output for invalid times
uint8 FILTER_DATE = 8 # Enable date output for invalid dates
uint8 FILTER_GPS_ONLY = 16 # Restrict output to GPS satellites only
uint8 FILTER_TRACK = 32 # Enable COG output even if COG is frozen
uint8 nmeaVersion # NMEA version
uint8 NMEA_VERSION_4_1 = 65 # Version 4.1
uint8 NMEA_VERSION_4_0 = 64 # Version 4.0
uint8 NMEA_VERSION_2_3 = 35 # Version 2.3
uint8 NMEA_VERSION_2_1 = 33 # Version 2.1
uint8 numSV # Maximum Number of SVs to report per TalkerId:
# unlimited (0) or 8, 12, 16
uint8 NUM_SV_UNLIMITED = 0
uint8 flags # flags
uint8 FLAGS_COMPAT = 1 # enable compatibility mode.
# This might be needed for certain applications
# when customer's NMEA parser expects a fixed
# number of digits in position coordinates
uint8 FLAGS_CONSIDER = 2 # enable considering mode
uint8 FLAGS_LIMIT82 = 4 # enable strict limit to 82 characters maximum
uint8 FLAGS_HIGH_PREC = 8 # enable high precision mode
# This flag cannot be set in conjunction with
# either Compatibility Mode or Limit82 Mode.
# (not supported in protocol versions < 20.01)
uint32 gnssToFilter # Filters out satellites based on their GNSS.
# If a bitfield is enabled, the corresponding
# satellites will be not output.
uint32 GNSS_TO_FILTER_GPS = 1 # Disable reporting of GPS satellites
uint32 GNSS_TO_FILTER_SBAS = 2 # Disable reporting of SBAS satellites
uint32 GNSS_TO_FILTER_QZSS = 16 # Disable reporting of QZSS satellites
uint32 GNSS_TO_FILTER_GLONASS = 32 # Disable reporting of GLONASS satellites
uint32 GNSS_TO_FILTER_BEIDOU = 64 # Disable reporting of BeiDou satellites
uint8 svNumbering # Configures the display of satellites that do not
# have an NMEA-defined value. Note: this does not
# apply to satellites with an unknown ID.
uint8 SV_NUMBERING_STRICT = 0 # Strict - Satellites are not output
uint8 SV_NUMBERING_EXTENDED = 1 # Extended - Use proprietary numbering
uint8 mainTalkerId # By default the main Talker ID (i.e. the Talker
# ID used for all messages other than GSV) is
# determined by the GNSS assignment of the
# receiver's channels (see CfgGNSS).
# This field enables the main Talker ID to be
# overridden
uint8 MAIN_TALKER_ID_NOT_OVERRIDDEN = 0 # Main Talker ID is not overridden
uint8 MAIN_TALKER_ID_GP = 1 # Set main Talker ID to 'GP'
uint8 MAIN_TALKER_ID_GL = 2 # Set main Talker ID to 'GL'
uint8 MAIN_TALKER_ID_GN = 3 # Set main Talker ID to 'GN'
uint8 MAIN_TALKER_ID_GA = 4 # Set main Talker ID to 'GA'
uint8 MAIN_TALKER_ID_GB = 5 # Set main Talker ID to 'GB'
uint8 gsvTalkerId # By default the Talker ID for GSV messages is
# GNSS specific (as defined by NMEA). This field
# enables the GSV Talker ID to be overridden.
uint8 GSV_TALKER_ID_GNSS_SPECIFIC = 0 # Use GNSS specific Talker ID
# (as defined by NMEA)
uint8 GSV_TALKER_ID_MAIN = 1 # Use the main Talker ID
uint8 version # Message version (set to 1 for this version)
uint8 VERSION = 1
uint8[2] bdsTalkerId # Sets the two characters that should be used
# for the BeiDou Talker ID. If these are set to
# zero, the default BeiDou TalkerId will be used
uint8[6] reserved1 # Reserved

View File

@@ -0,0 +1,39 @@
# CFG-NMEA (0x06 0x17)
# NMEA protocol configuration
#
# Set/Get the NMEA protocol configuration. See section NMEA Protocol
# Configuration for a detailed description of the configuration effects on
# NMEA output
#
# Supported on u-blox 6 from firmware version 6.00 up to version 7.03.
#
uint8 CLASS_ID = 6
uint8 MESSAGE_ID = 23
uint8 filter # filter flags
uint8 FILTER_POS = 1 # Disable position filtering
uint8 FILTER_MSK_POS = 2 # Disable masked position filtering
uint8 FILTER_TIME = 4 # Disable time filtering
uint8 FILTER_DATE = 8 # Disable date filtering
uint8 FILTER_SBAS_FILT = 16 # Enable SBAS filtering
uint8 FILTER_TRACK = 32 # Disable track filtering
uint8 version # NMEA version
uint8 NMEA_VERSION_2_3 = 35 # Version 2.3
uint8 NMEA_VERSION_2_1 = 33 # Version 2.1
uint8 numSV # Maximum Number of SVs to report in NMEA
# protocol.
# This does not affect the receiver's operation.
# It only limits the number of SVs reported in
# NMEA mode (this might be needed with older
# mapping applications which only support 8- or
# 12-channel receivers)
uint8 flags # flags
uint8 FLAGS_COMPAT = 1 # enable compatibility mode.
# This might be needed for certain applications
# when customer's NMEA parser expects a fixed
# number of digits in position coordinates
uint8 FLAGS_CONSIDER = 2 # enable considering mode

View File

@@ -0,0 +1,70 @@
# CFG-NMEA (0x06 0x17)
# NMEA protocol configuration V0
#
# Set/Get the NMEA protocol configuration. See section NMEA Protocol
# Configuration for a detailed description of the configuration effects on
# NMEA output
#
# Supported on: u-blox 7 firmware version 1.00
#
uint8 CLASS_ID = 6
uint8 MESSAGE_ID = 23
uint8 filter # filter flags
uint8 FILTER_POS = 1 # Enable position output for failed or
# invalid fixes
uint8 FILTER_MSK_POS = 2 # Enable position output for invalid fixes
uint8 FILTER_TIME = 4 # Enable time output for invalid times
uint8 FILTER_DATE = 8 # Enable date output for invalid dates
uint8 FILTER_GPS_ONLY = 16 # Restrict output to GPS satellites only
uint8 FILTER_TRACK = 32 # Enable COG output even if COG is frozen
uint8 nmeaVersion # NMEA version
uint8 NMEA_VERSION_2_3 = 35 # Version 2.3
uint8 NMEA_VERSION_2_1 = 33 # Version 2.1
uint8 numSV # Maximum Number of SVs to report per TalkerId:
# unlimited (0) or 8, 12, 16
uint8 NUM_SV_UNLIMITED = 0
uint8 flags # flags
uint8 FLAGS_COMPAT = 1 # enable compatibility mode.
# This might be needed for certain applications
# when customer's NMEA parser expects a fixed
# number of digits in position coordinates
uint8 FLAGS_CONSIDER = 2 # enable considering mode
uint32 gnssToFilter # Filters out satellites based on their GNSS.
# If a bitfield is enabled, the corresponding
# satellites will be not output.
uint32 GNSS_TO_FILTER_GPS = 1 # Disable reporting of GPS satellites
uint32 GNSS_TO_FILTER_SBAS = 2 # Disable reporting of SBAS satellites
uint32 GNSS_TO_FILTER_QZSS = 16 # Disable reporting of QZSS satellites
uint32 GNSS_TO_FILTER_GLONASS = 32 # Disable reporting of GLONASS satellites
uint8 svNumbering # Configures the display of satellites that do not
# have an NMEA-defined value. Note: this does not
# apply to satellites with an unknown ID.
uint8 SV_NUMBERING_STRICT = 0 # Strict - Satellites are not output
uint8 SV_NUMBERING_EXTENDED = 1 # Extended - Use proprietary numbering
uint8 mainTalkerId # By default the main Talker ID (i.e. the Talker
# ID used for all messages other than GSV) is
# determined by the GNSS assignment of the
# receiver's channels (see CfgGNSS).
# This field enables the main Talker ID to be
# overridden
uint8 MAIN_TALKER_ID_NOT_OVERRIDDEN = 0 # Main Talker ID is not overridden
uint8 MAIN_TALKER_ID_GP = 1 # Set main Talker ID to 'GP'
uint8 MAIN_TALKER_ID_GL = 2 # Set main Talker ID to 'GL'
uint8 MAIN_TALKER_ID_GN = 3 # Set main Talker ID to 'GN'
uint8 gsvTalkerId # By default the Talker ID for GSV messages is
# GNSS specific (as defined by NMEA). This field
# enables the GSV Talker ID to be overridden.
uint8 GSV_TALKER_ID_GNSS_SPECIFIC = 0 # Use GNSS specific Talker ID
# (as defined by NMEA)
uint8 GSV_TALKER_ID_MAIN = 1 # Use the main Talker ID
uint8 reserved # Reserved

View File

@@ -0,0 +1,105 @@
# CFG-PRT (0x06 0x00)
# Port Configuration for DDC, UART, USB, SPI
#
# Several configurations can be concatenated to one input message. In this case
# the payload length can be a multiple of the normal length (see the other
# versions of CFG-PRT). Output messages from the module contain only one
# configuration unit.
#
uint8 CLASS_ID = 6
uint8 MESSAGE_ID = 0
uint8 portID # Port Identifier Number
uint8 PORT_ID_DDC = 0
uint8 PORT_ID_UART1 = 1
uint8 PORT_ID_UART2 = 2
uint8 PORT_ID_USB = 3
uint8 PORT_ID_SPI = 4
uint8 reserved0 # Reserved
uint16 txReady # TX ready PIN configuration (since Firmware 7.01)
# reserved (Always set to zero) up to Firmware 7.01
uint16 TX_READY_EN = 1 # Enable TX ready feature for this
# port
uint16 TX_READY_POLARITY_HIGH_ACTIVE = 0 # Polarity High-active
uint16 TX_READY_POLARITY_LOW_ACTIVE = 2 # Polarity Low-active
uint16 TX_READY_PIN_SHIFT = 2 # PIO to be used (must not be in use
# already by another function)
uint16 TX_READY_PIN_MASK = 124 #
uint16 TX_READY_THRES_SHIFT = 7 # Threshold
uint16 TX_READY_THRES_MASK = 65408 # The given threshold is multiplied by
# 8 bytes.
# The TX ready PIN goes active
# after >= thres*8 bytes are pending
# for the port and going inactive
# after the last pending bytes have
# been written to hardware (0-4 bytes
# before end of stream).
uint32 mode # A bit mask describing the DDC, UART or SPI mode
# Reserved for USB
# DDC Mode Constants
uint32 MODE_DDC_SLAVE_ADDR_SHIFT = 1
uint32 MODE_DDC_SLAVE_ADDR_MASK = 254 # Slave address
# Range: 0x07 < slaveAddr < 0x78.
# UART Mode Constants
uint32 MODE_RESERVED1 = 16 # Default 1 for compatibility with A4
uint32 MODE_CHAR_LEN_MASK = 192 # Character Length
uint32 MODE_CHAR_LEN_5BIT = 0 # 5bit (not supported)
uint32 MODE_CHAR_LEN_6BIT = 64 # 6bit (not supported)
uint32 MODE_CHAR_LEN_7BIT = 128 # 7bit (supported only with parity)
uint32 MODE_CHAR_LEN_8BIT = 192 # 8bit
uint32 MODE_PARITY_MASK = 3584 #
uint32 MODE_PARITY_EVEN = 0 # Even Parity
uint32 MODE_PARITY_ODD = 512 # Odd Parity
uint32 MODE_PARITY_NO = 2048 # No Parity (even/odd ignored)
uint32 MODE_STOP_BITS_MASK = 12288 # Number of Stop Bits
uint32 MODE_STOP_BITS_1 = 0 # 1 Stop Bit
uint32 MODE_STOP_BITS_15 = 4096 # 1.5 Stop Bit
uint32 MODE_STOP_BITS_2 = 8192 # 2 Stop Bit
uint32 MODE_STOP_BITS_05 = 12288 # 0.5 Stop Bit
# SPI Mode Constants
uint32 MODE_SPI_SPI_MODE_CPOL = 4 # SPI Mode CPOL (0/1)
uint32 MODE_SPI_SPI_MODE_CPHA = 2 # SPI Mode CPH (0/1)
# (both CPOL/CPHA) can be = 1
uint32 MODE_SPI_FLOW_CONTROL = 64 # (u-blox 6 only)
# 0 Flow control disabled
# 1 Flow control enabled (9-bit mode)
uint32 MODE_SPI_FF_COUNT_SHIFT = 8
uint32 MODE_SPI_FF_COUNT_MASK = 16128 # Number of bytes containing 0xFF to
# receive before switching off
# reception.
# Range: 0(mechanism off)-63
uint32 baudRate # UART Baudrate in bits/second [bits/s]
# Reserved for USB, SPI, DDC
# Possible values: 4800, 9600, 19200, 38400, 57600,
# 115200, 230400, 460800
uint16 inProtoMask # A mask describing which input protocols are active.
# Each bit of this mask is used for a protocol.
# Through that, multiple protocols can be defined
# on a single port.
uint16 outProtoMask # A mask describing which output protocols are active.
# Each bit of this mask is used for a protocol.
# Through that, multiple protocols can be defined
# on a single port.
uint16 PROTO_UBX = 1
uint16 PROTO_NMEA = 2
uint16 PROTO_RTCM = 4 # only for inProtoMask
uint16 PROTO_RTCM3 = 32 # (not supported in protocol versions less than 20)
uint16 flags # Flags for UART & SPI, Reserved for USB
uint16 FLAGS_EXTENDED_TX_TIMEOUT = 2 # if set, the port will timeout if
# allocated TX memory >=4 kB and no
# activity for 1.5s. If not set the port
# will timoout if no activity for 1.5s
# regardless on the amount of allocated
# TX memory.
uint16 reserved1 # Always set to zero

View File

@@ -0,0 +1,33 @@
# CFG-RATE (0x06 0x08)
# Navigation/Measurement Rate Settings
#
# This message allows the user to alter the rate at which navigation solutions
# (and the measurements that they depend on) are generated by the receiver. The
# calculation of the navigation solution will always be aligned to the top of a
# second zero (first second of the week) of the configured reference time
# system. For protocol version 18 and later the navigation period is an integer
# multiple of the measurement period.
# - Each measurement triggers the measurements generation and raw data output.
# - The navRate value defines that every nth measurement triggers a navigation
# epoch.
# - The update rate has a direct influence on the power consumption. The more
# fixes that are required, the more CPU power and communication resources
# are required.
# - For most applications a 1 Hz update rate would be sufficient.
# - When using Power Save Mode, measurement and navigation rate can differ from
# the values configured here
uint8 CLASS_ID = 6
uint8 MESSAGE_ID = 8
uint16 measRate # Measurement Rate, GPS measurements are
# taken every measRate milliseconds [ms]
uint16 navRate # Navigation Rate, in number of measurement
# cycles. On u-blox 5 and u-blox 6, this parameter
# cannot be changed, and always equals 1.
uint16 timeRef # The time system to which measurements are aligned
uint16 TIME_REF_UTC = 0
uint16 TIME_REF_GPS = 1
uint16 TIME_REF_GLONASS = 2 # not supported in protocol versions less than 18
uint16 TIME_REF_BEIDOU = 3 # not supported in protocol versions less than 18
uint16 TIME_REF_GALILEO = 4 # not supported in protocol versions less than 18

View File

@@ -0,0 +1,38 @@
# CFG-RST (0x06 0x04)
# Reset Receiver / Clear Backup Data Structures
#
# Don't expect this message to be acknowledged by the receiver.
# - Newer FW version won't acknowledge this message at all.
# - Older FW version will acknowledge this message but the acknowledge may not
# be sent completely before the receiver is reset.
#
uint8 CLASS_ID = 6
uint8 MESSAGE_ID = 4
uint16 navBbrMask # BBR Sections to clear.
# The following Special Sets apply:
uint16 NAV_BBR_HOT_START = 0 # Hot start the device
uint16 NAV_BBR_WARM_START = 1 # Warm start the device
uint16 NAV_BBR_COLD_START = 65535 # Cold start the device
uint16 NAV_BBR_EPH = 1 # Ephemeris
uint16 NAV_BBR_ALM = 2 # Almanac
uint16 NAV_BBR_HEALTH = 4 # Health
uint16 NAV_BBR_KLOB = 8 # Klobuchar parameters
uint16 NAV_BBR_POS = 16 # Position
uint16 NAV_BBR_CLKD = 32 # Clock Drift
uint16 NAV_BBR_OSC = 64 # Oscillator Parameter
uint16 NAV_BBR_UTC = 128 # UTC Correction + GPS Leap Seconds Parameters
uint16 NAV_BBR_RTC = 256 # RTC
uint16 NAV_BBR_AOP = 32768 # Autonomous Orbit Parameters
uint8 resetMode # Reset Type:
uint8 RESET_MODE_HW_IMMEDIATE = 0 # Hardware reset (Watchdog) immediately
uint8 RESET_MODE_SW = 1 # Controlled Software reset
uint8 RESET_MODE_GNSS = 2 # Controlled Software reset (GNSS only)
uint8 RESET_MODE_HW_AFTER_SHUTDOWN = 4 # Hardware reset (Watchdog) after
# shutdown
uint8 RESET_MODE_GNSS_STOP = 8 # Controlled GNSS stop
uint8 RESET_MODE_GNSS_START = 9 # Controlled GNSS start
uint8 reserved1 # Reserved

View File

@@ -0,0 +1,36 @@
# CFG-SBAS (0x06 0x16)
# SBAS Configuration
#
# This message configures the SBAS receiver subsystem (i.e. WAAS, EGNOS, MSAS).
# See the SBAS Configuration Settings Description for a detailed description of
# how these settings affect receiver operation
#
uint8 CLASS_ID = 6
uint8 MESSAGE_ID = 22
uint8 mode # SBAS Mode
uint8 MODE_ENABLED = 1 # SBAS Enabled (1) / Disabled (0)
# This field is deprecated; use UBX-CFG-GNSS to
# enable/disable SBAS operation
uint8 MODE_TEST = 2 # SBAS Testbed: Use data anyhow (1) / Ignore data when
# in Test Mode (SBAS Msg 0)
uint8 usage # SBAS Usage
uint8 USAGE_RANGE = 1 # Use SBAS GEOs as a ranging source (for navigation)
uint8 USAGE_DIFF_CORR = 2 # Use SBAS Differential Corrections
uint8 USAGE_INTEGRITY = 4 # Use SBAS Integrity Information
uint8 maxSBAS # Maximum Number of SBAS prioritized tracking
# channels (valid range: 0 - 3) to use
# (obsolete and superseeded by UBX-CFG-GNSS in protocol
# versions 14+).
uint8 scanmode2 # Continuation of scanmode bitmask below
# PRN 152...158
uint32 scanmode1 # Which SBAS PRN numbers to search for (Bitmask)
# If all Bits are set to zero, auto-scan (i.e. all valid
# PRNs) are searched. Every bit corresponds to a PRN
# number.
# PRN 120..151

View File

@@ -0,0 +1,68 @@
# CFG-TMODE3 (0x06, 0x71)
# Time Mode Settings 3
#
# Configures the receiver to be in Time Mode. The position referred to in this
# message is that of the Antenna Reference Point (ARP). See the Time Mode
# Description for details.
#
# Supported on:
# - u-blox 8 / u-blox M8 with protocol version 20 (only with High Precision
# GNSS products)
#
uint8 CLASS_ID = 6
uint8 MESSAGE_ID = 113
uint8 version # Message version (0x00 for this version)
uint8 reserved1 # Reserved
uint16 flags
uint16 FLAGS_MODE_MASK = 255 # Receiver Mode:
uint16 FLAGS_MODE_DISABLED = 0 # Disabled
uint16 FLAGS_MODE_SURVEY_IN = 1 # Survey In
uint16 FLAGS_MODE_FIXED = 2 # Fixed Mode (true ARP position required)
uint16 FLAGS_LLA = 256 # Position is given in LAT/LON/ALT
# (default is ECEF)
int32 ecefXOrLat # WGS84 ECEF X coordinate (or latitude) of
# the ARP position, depending on flags above
# [cm] or [deg / 1e-7]
int32 ecefYOrLon # WGS84 ECEF Y coordinate (or longitude) of
# the ARP position, depending on flags above
# [cm] or [deg / 1e-7]
int32 ecefZOrAlt # WGS84 ECEF Z coordinate (or altitude) of
# the ARP position, depending on flags above
# [cm]
int8 ecefXOrLatHP # High-precision WGS84 ECEF X coordinate (or
# latitude) of the ARP position, depending on
# flags above. Must be in the range -99..+99.
# The precise WGS84 ECEF X coordinate in units
# of cm, or the precise WGS84 ECEF latitude in
# units of 1e-7 degrees, is given by
# ecefXOrLat + (ecefXOrLatHP * 1e-2)
# [0.1 mm] or [deg * 1e-9]
int8 ecefYOrLonHP # High-precision WGS84 ECEF Y coordinate (or
# longitude) of the ARP position, depending on
# flags above. Must be in the range -99..+99.
# The precise WGS84 ECEF Y coordinate in units
# of cm, or the precise WGS84 ECEF longitude
# in units of 1e-7 degrees, is given by
# ecefYOrLon + (ecefYOrLonHP * 1e-2)
# [0.1 mm] or [deg * 1e-9]
int8 ecefZOrAltHP # High-precision WGS84 ECEF Z coordinate (or
# altitude) of the ARP position, depending on
# flags above. Must be in the range -99..+99.
# The precise WGS84 ECEF Z coordinate, or
# altitude coordinate, in units of cm is given
# by ecefZOrAlt + (ecefZOrAltHP * 1e-2)
# [0.1 mm]
uint8 reserved2 # Reserved
uint32 fixedPosAcc # Fixed position 3D accuracy
# [0.1 mm]
uint32 svinMinDur # Survey-in minimum duration
# [s]
uint32 svinAccLimit # Survey-in position accuracy limit
# [0.1 mm]
uint8[8] reserved3 # Reserved

View File

@@ -0,0 +1,30 @@
# UBX-CFG-USB (0x06 0x1B)
# USB Configuration
#
uint8 CLASS_ID = 6
uint8 MESSAGE_ID = 27
uint16 vendorID # Only set to registered Vendor IDs.
# Changing this field requires special Host drivers.
uint16 productID # Product ID. Changing this field requires special
# Host drivers.
uint8[2] reserved1 # Reserved
uint8[2] reserved2 # Reserved
uint16 powerConsumption # Power consumed by the device [mA]
uint16 flags # various configuration flags (see graphic below)
uint16 FLAGS_RE_ENUM = 0 # force re-enumeration
uint16 FLAGS_POWER_MODE = 2 # self-powered (1), bus-powered (0)
int8[32] vendorString # String containing the vendor name.
# 32 ASCII bytes including 0-termination.
int8[32] productString # String containing the product name.
# 32 ASCII bytes including 0-termination.
int8[32] serialNumber # String containing the serial number.
# 32 ASCII bytes including 0-termination.
# Changing the String fields requires special Host
# drivers.

View File

@@ -0,0 +1,38 @@
# ESF-INS (0x10 0x15)
# Vehicle dynamics information
#
# This message outputs information about vehicle dynamics computed by the
# Inertial Navigation System (INS) during ESF-based navigation.
# For ADR products, the output dynamics information (angular rates and
# accelerations) is expressed with respect to the vehicle-frame.
# For UDR products, the output dynamics information (angular rates and
# accelerations) is expressed with respect to the body-frame.
#
uint8 CLASS_ID = 16
uint8 MESSAGE_ID = 21
uint32 bitfield0 # Bitfield (see graphic below)
uint32 BITFIELD0_VERSION = 255 # Message version (1 for this version).
uint32 BITFIELD0_X_ANG_RATE_VALID = 256 # Compensated x-axis angular rate data
# validity flag
uint32 BITFIELD0_Y_ANG_RATE_VALID = 512 # Compensated y-axis angular rate data
# validity flag
uint32 BITFIELD0_Z_ANG_RATE_VALID = 1024 # Compensated z-axis angular rate data
# validity flag
uint32 BITFIELD0_X_ACCEL_VALID = 2048 # Compensated x-axis acceleration data
# validity flag
uint32 BITFIELD0_Y_ACCEL_VALID = 4096 # Compensated y-axis acceleration data
# validity flag
uint32 BITFIELD0_Z_ACCEL_VALID = 8192 # Compensated z-axis acceleration data
# validity flag
uint8[4] reserved1 # Reserved
uint32 iTOW # GPS time of week of the navigation epoch [ms]
int32 xAngRate # Compensated x-axis angular rate [deg/s / 1e-3]
int32 yAngRate # Compensated y-axis angular rate [deg/s / 1e-3]
int32 zAngRate # Compensated z-axis angular rate [deg/s / 1e-3]
int32 xAccel # Compensated x-axis acceleration (gravity-free) [mg]
int32 yAccel # Compensated y-axis acceleration (gravity-free) [mg]
int32 zAccel # Compensated z-axis acceleration (gravity-free) [mg]

View File

@@ -0,0 +1,77 @@
# ESF-MEAS (0x10 0x02)
# External Sensor Fusion Measurements
#
# Possible data types for the data field are described in the ESF Measurement
# Data section
#
uint8 CLASS_ID = 16
uint8 MESSAGE_ID = 2
uint32 timeTag # Time tag of measurement generated by external
# sensor
uint16 flags # Flags. Set all unused bits to zero:
uint16 FLAGS_TIME_MARK_SENT_MASK = 3 # Time mark signal was supplied just
# prior to sending this message: 0 =
uint16 TIME_MARK_NONE = 0
uint16 TIME_MARK_EXT0 = 1
uint16 TIME_MARK_EXT = 2
uint16 FLAGS_TIME_MARK_EDGE = 4 # Trigger on rising (0) or falling
# (1) edge of time mark signal
uint16 FLAGS_CALIB_T_TAG_VALID = 8 # Calibration time tag available.
# Always set to zero.
uint16 id # Identification number of data provider
# Start of repeated block (N times)
uint32[] data # data, see mask below
uint32 DATA_FIELD_MASK = 16777215 # data
uint32 DATA_TYPE_MASK = 1056964608 # type of data (1..63)
uint32 DATA_TYPE_SHIFT = 24
uint32 DATA_TYPE_NONE = 0 # data field contains no data
uint32 DATA_TYPE_Z_AXIS_GYRO = 5 # z-axis gyroscope angular rate
# [deg/s *2^-12 signed]
uint32 DATA_TYPE_WHEEL_TICKS_FRONT_LEFT = 6 # front-left wheel ticks
# Bits 0-22: unsigned tick value.
# Bit 23: direction indicator
# (0=forward, 1=backward)
uint32 DATA_TYPE_WHEEL_TICKS_FRONT_RIGHT = 7 # front-right wheel ticks
# Bits 0-22: unsigned tick value.
# Bit 23: direction indicator
# (0=forward, 1=backward)
uint32 DATA_TYPE_WHEEL_TICKS_REAR_LEFT = 8 # rear-left wheel ticks
# Bits 0-22: unsigned tick value.
# Bit 23: direction indicator
# (0=forward, 1=backward)
uint32 DATA_TYPE_WHEEL_TICKS_REAR_RIGHT = 9 # rear-right wheel ticks
# Bits 0-22: unsigned tick value.
# Bit 23: direction indicator
# (0=forward, 1=backward)
uint32 DATA_TYPE_SINGLE_TICK = 10 # single tick (speed tick)
# Bits 0-22: unsigned tick value.
# Bit 23: direction indicator
# (0=forward, 1=backward)
uint32 DATA_TYPE_SPEED = 11 # speed m/s * 1e-3 signed
uint32 DATA_TYPE_GYRO_TEMPERATURE = 12 # gyroscope temperature
# [deg Celsius * 1e-2 signed]
uint32 DATA_TYPE_GYRO_ANG_RATE_Y = 13 # y-axis gyroscope angular rate
# [deg/s *2^-12 signed]
uint32 DATA_TYPE_GYRO_ANG_RATE_X = 14 # x-axis gyroscope angular rate
# [deg/s *2^-12 signed]
uint32 DATA_TYPE_ACCELEROMETER_X = 16 # x-axis accelerometer specific
# [force m/s^2 *2^-10 signed]
uint32 DATA_TYPE_ACCELEROMETER_Y = 17 # y-axis accelerometer specific
# [force m/s^2 *2^-10 signed]
uint32 DATA_TYPE_ACCELEROMETER_Z = 18 # z-axis accelerometer specific
# [force m/s^2 *2^-10 signed]
# End of repeated block
# Start of optional block (size is either 0 or 1)
uint32[] calibTtag # Receiver local time calibrated.
# This field must not be supplied when
# calibTtagValid is set to 0 [ms]
# End of optional block

View File

@@ -0,0 +1,18 @@
# ESF-RAW (0x10 0x03)
# Raw sensor measurements
#
# The message contains measurements from the active inertial sensors connected
# to the GNSS chip. Possible data types for the data field are accelerometer,
# gyroscope and temperature readings as described in the ESF Measurement Data
# section. Note that the rate selected in CFG-MSG is not respected. If a
# positive rate is selected then all raw measurements will be output.
#
# Supported on ADR/UDR products.
#
uint8 CLASS_ID = 16
uint8 MESSAGE_ID = 3
uint8[4] reserved0 # Reserved
EsfRAW_Block[] blocks

View File

@@ -0,0 +1,8 @@
# See ESF-RAW
uint32 data # Its scaling and unit depends on the type and is
# the same as in ESF-MEAS
uint32 DATA_FIELD_MASK = 16777215
uint32 DATA_TYPE_MASK = 4278190080 # type of data
# (0 = no data; 1..255 = data type)
uint32 sTtag # sensor time tag

View File

@@ -0,0 +1,34 @@
# ESF-STATUS (0x10 0x10)
# External Sensor Fusion (ESF) status information
#
# Supported on UDR/ADR products
#
uint8 CLASS_ID = 16
uint8 MESSAGE_ID = 16
uint32 iTOW # GPS time of week of the navigation epoch [ms]
uint8 version # Message version (2 for this version)
uint8[7] reserved1 # Reserved
uint8 fusionMode # Fusion mode:
uint8 FUSION_MODE_INIT = 0 # receiver is initializing some unknown values
# required for doing sensor fusion
uint8 FUSION_MODE_FUSION = 1 # GNSS and sensor data are
# used for navigation solution computation
uint8 FUSION_MODE_SUSPENDED = 2 # sensor fusion is temporarily disabled
# due to e.g. invalid sensor data or detected
# ferry
uint8 FUSION_MODE_DISABLED = 3 # sensor fusion is permanently disabled
# until receiver reset due e.g. to sensor
# error
uint8[2] reserved2 # Reserved
uint8 numSens # Number of sensors
# Start of repeated block (numSens times)
EsfSTATUS_Sens[] sens
# End of repeated block

View File

@@ -0,0 +1,7 @@
# See Esf-STATUS
#
uint8 sensStatus1 # Sensor status, part 1 (see graphic below)
uint8 sensStatus2 # Sensor status, part 2 (see graphic below)
uint8 freq # Observation frequency [Hz]
uint8 faults # Sensor faults (see graphic below)

View File

@@ -0,0 +1,67 @@
# HNR-PVT (0x28 0x00)
# High Rate Output of PVT Solution
#
# Note that during a leap second there may be more (or less) than 60 seconds in
# a minute; see the description of leap seconds for details.
#
# This message provides the position, velocity and time solution with high
# output rate.
#
# Supported on ADR and UDR products.
#
uint8 CLASS_ID = 40
uint8 MESSAGE_ID = 0
uint32 iTOW # GPS Millisecond time of week [ms]
uint16 year # Year (UTC)
uint8 month # Month, range 1..12 (UTC)
uint8 day # Day of month, range 1..31 (UTC)
uint8 hour # Hour of day, range 0..23 (UTC)
uint8 min # Minute of hour, range 0..59 (UTC)
uint8 sec # Seconds of minute, range 0..60 (UTC)
uint8 valid # Validity flags
uint8 VALID_DATE = 1 # Valid UTC Date
uint8 VALID_TIME = 2 # Valid
uint8 VALID_FULLY_RESOLVED = 4 # UTC time of day has been fully resolved
# (no seconds uncertainty)
uint8 VALID_MAG = 8 # Valid Magnetic Declination
int32 nano # fraction of a second [ns], range -1e9 .. 1e9 (UTC)
uint8 gpsFix # GPS fix Type, range 0..5
uint8 FIX_TYPE_NO_FIX = 0
uint8 FIX_TYPE_DEAD_RECKONING_ONLY = 1
uint8 FIX_TYPE_2D = 2 # Signal from only 3 SVs,
# constant altitude assumed
uint8 FIX_TYPE_3D = 3
uint8 FIX_TYPE_GPS_DEAD_RECKONING_COMBINED = 4 # GPS + Dead reckoning
uint8 FIX_TYPE_TIME_ONLY = 5 # Time only fix
uint8 flags # Fix Status Flags
uint8 FLAGS_GNSS_FIX_OK = 1 # i.e. within DOP & accuracy masks
uint8 FLAGS_DIFF_SOLN = 2 # DGPS used
uint8 FLAGS_WKN_SET = 4 # Valid GPS week number
uint8 FLAGS_TOW_SET = 8 # Valid GPS time of week (iTOW & fTOW)
uint8 FLAGS_HEAD_VEH_VALID = 32 # heading of vehicle is valid
uint8[2] reserved0 # Reserved
int32 lon # Longitude [deg / 1e-7]
int32 lat # Latitude [deg / 1e-7]
int32 height # Height above Ellipsoid [mm]
int32 hMSL # Height above mean sea level [mm]
int32 gSpeed # Ground Speed (2-D) [mm/s]
int32 speed # Speed (3-D) [mm/s]
int32 headMot # Heading of motion (2-D) [deg / 1e-5]
int32 headVeh # Heading of vehicle (2-D) [deg / 1e-5]
uint32 hAcc # Horizontal Accuracy Estimate [mm]
uint32 vAcc # Vertical Accuracy Estimate [mm]
uint32 sAcc # Speed Accuracy Estimate [mm/s]
uint32 headAcc # Heading Accuracy Estimate (both motion & vehicle)
# [deg / 1e-5]
uint8[4] reserved1 # Reserved

View File

@@ -0,0 +1,9 @@
# UBX-INF (0x04, 0x00...0x04)
# ASCII output
#
# This message has a variable length payload, representing an ASCII string.
#
uint8 CLASS_ID = 4
char[] str

View File

@@ -0,0 +1,61 @@
# MGA-GAL (0x13 0x02)
# Galileo Ephemeris Assistance
#
# This message allows the delivery of Galileo ephemeris assistance to a
# receiver. See the description of AssistNow Online for details.
#
uint8 CLASS_ID = 19
uint8 MESSAGE_ID = 2
uint8 type # Message type (0x01 for this type)
uint8 version # Message version (0x00 for this version)
uint8 svid # Galileo Satellite identifier
uint8 reserved0 # Reserved
uint16 iodNav # Ephemeris and clock correction issue of Data
int16 deltaN # Mean motion difference from computed value
# [semi-cir cles/s * 2^-43]
int32 m0 # Mean anomaly at reference time [semi-cir cles 2^-31]
uint32 e # Eccentricity [2^-33]
uint32 sqrtA # Square root of the semi-major axis [m^0.5 * 2^-19]
int32 omega0 # Longitude of ascending node of orbital plane at weekly
# epoch [semi-cir cles 2^-31]
int32 i0 # inclination angle at reference time
# [semi-cir cles 2^-31]
int32 omega # Argument of perigee [semi-cir cles 2^-31]
int32 omegaDot # Rate of change of right ascension
# [semi-cir cles/s 2^-43]
int16 iDot # Rate of change of inclination angle
# [semi-cir cles/s 2^-43]
int16 cuc # Amplitude of the cosine harmonic correction term to
# the argument of latitude [radians * 2^-29]
int16 cus # Amplitude of the sine harmonic correction term to
# the argument of latitude [radians * 2^-29]
int16 crc # Amplitude of the cosine harmonic correction term
# to the orbit radius [radians * 2^-5]
int16 crs # Amplitude of the sine harmonic correction term to the
# orbit radius [radians * 2^-5]
int16 cic # Amplitude of the cosine harmonic correction term to
# the angle of inclination [radians * 2^-29]
int16 cis # Amplitude of the sine harmonic correction term to the
# angle of inclination [radians * 2^-29]
uint16 toe # Ephemeris reference time [60 * s]
int32 af0 # clock bias correction coefficient [s * 2^-34]
int32 af1 # SV clock drift correction coefficient [s/s * 2^-46]
int8 af2 # SV clock drift rate correction coefficient
# [s/s^2 * 2^-59]
uint8 sisaindexE1E5b # Signal-in-Space Accuracy index for dual frequency
# E1-E5b
uint16 toc # Clock correction data reference Time of Week [60 * s]
int16 bgdE1E5b # E1-E5b Broadcast Group Delay
uint8[2] reserved1 # Reserved
uint8 healthE1B # E1-B Signal Health Status
uint8 dataValidityE1B # E1-B Data Validity Status
uint8 healthE5b # E5b Signal Health Status
uint8 dataValidityE5b # E5b Data Validity Status
uint8[4] reserved2 # Reserved

View File

@@ -0,0 +1,31 @@
# MON-GNSS (0x0A 0x28)
# Information message major GNSS selection
#
# This message reports major GNSS selection. Augmentation systems are not
# reported.
#
uint8 CLASS_ID = 10
uint8 MESSAGE_ID = 40
uint8 version # Message version (0x01 for this version)
uint8 BIT_MASK_GPS = 1
uint8 BIT_MASK_GLONASS = 2
uint8 BIT_MASK_BEIDOU = 4
uint8 BIT_MASK_GALILEO = 8
uint8 supported # The major GNSS that can be supported by this receiver
uint8 defaultGnss # Default major GNSS selection. If the default major GNSS
# selection is currently configured in the efuse for this
# receiver, it takes precedence over the default major
# GNSS selection configured in the executing firmware of
# this receiver.
# see bit mask constants
uint8 enabled # Current major GNSS selection enabled for this receiver
# see bit mask constants
uint8 simultaneous # Maximum number of concurrent major GNSS that can be
# supported by this receiver
uint8[3] reserved1 # Reserved

View File

@@ -0,0 +1,57 @@
# MON-HW (0x0A 0x09)
# Hardware Status
#
# Status of different aspect of the hardware, such as Antenna, PIO/Peripheral
# Pins, Noise Level, Automatic Gain Control (AGC)
#
# WARNING: this message is a different length than the MonHW message for
# firmware version 6
uint8 CLASS_ID = 10
uint8 MESSAGE_ID = 9
uint32 pinSel # Mask of Pins Set as Peripheral/PIO
uint32 pinBank # Mask of Pins Set as Bank A/B
uint32 pinDir # Mask of Pins Set as Input/Output
uint32 pinVal # Mask of Pins Value Low/High
uint16 noisePerMS # Noise Level as measured by the GPS Core
uint16 agcCnt # AGC Monitor (counts SIGHI xor SIGLO,
# range 0 to 8191)
uint8 aStatus # Status of the Antenna Supervisor State Machine
uint8 A_STATUS_INIT = 0
uint8 A_STATUS_UNKNOWN = 1
uint8 A_STATUS_OK = 2
uint8 A_STATUS_SHORT = 3
uint8 A_STATUS_OPEN = 4
uint8 aPower # Current PowerStatus of Antenna
uint8 A_POWER_OFF = 0
uint8 A_POWER_ON = 1
uint8 A_POWER_UNKNOWN = 2
uint8 flags # Flags:
uint8 FLAGS_RTC_CALIB = 1 # RTC is calibrated
uint8 FLAGS_SAFE_BOOT = 2 # Safe boot mode (0 = inactive, 1 = active)
uint8 FLAGS_JAMMING_STATE_MASK = 12 # output from Jamming/Interference Monitor:
uint8 JAMMING_STATE_UNKNOWN_OR_DISABLED = 0 # unknown or feature disabled
uint8 JAMMING_STATE_OK = 4 # ok - no significant jamming
uint8 JAMMING_STATE_WARNING = 8 # interference visible but fix OK
uint8 JAMMING_STATE_CRITICAL = 12 # interference visible and no fix
uint8 FLAGS_XTAL_ABSENT = 16 # RTC XTAL is absent
# (not supported in protocol versions < 18)
uint8 reserved0 # Reserved
uint32 usedMask # Mask of Pins that are used by the Virtual Pin
# Manager
uint8[17] VP # Array of Pin Mappings for each of the 17
# Physical Pins
uint8 jamInd # CW Jamming indicator, scaled:
uint8 JAM_IND_NONE = 0 # No CW Jamming
uint8 JAM_IND_STRONG = 255 # Strong CW Jamming
uint8[2] reserved1 # Reserved
uint32 pinIrq # Mask of Pins Value using the PIO Irq
uint32 pullH # Mask of Pins Value using the PIO Pull High
# Resistor
uint32 pullL # Mask of Pins Value using the PIO Pull Low
# Resistor

View File

@@ -0,0 +1,58 @@
# MON-HW (0x0A 0x09)
# Hardware Status
# Firmware 6
#
# Status of different aspect of the hardware, such as Antenna, PIO/Peripheral
# Pins, Noise Level, Automatic Gain Control (AGC)
#
# WARNING: this message is a different length than the MonHW message for
# firmware version 7 & 8
uint8 CLASS_ID = 10
uint8 MESSAGE_ID = 9
uint32 pinSel # Mask of Pins Set as Peripheral/PIO
uint32 pinBank # Mask of Pins Set as Bank A/B
uint32 pinDir # Mask of Pins Set as Input/Output
uint32 pinVal # Mask of Pins Value Low/High
uint16 noisePerMS # Noise Level as measured by the GPS Core
uint16 agcCnt # AGC Monitor (counts SIGHI xor SIGLO,
# range 0 to 8191)
uint8 aStatus # Status of the Antenna Supervisor State Machine
uint8 A_STATUS_INIT = 0
uint8 A_STATUS_UNKNOWN = 1
uint8 A_STATUS_OK = 2
uint8 A_STATUS_SHORT = 3
uint8 A_STATUS_OPEN = 4
uint8 aPower # Current PowerStatus of Antenna
uint8 A_POWER_OFF = 0
uint8 A_POWER_ON = 1
uint8 A_POWER_UNKNOWN = 2
uint8 flags # Flags:
uint8 FLAGS_RTC_CALIB = 1 # RTC is calibrated
uint8 FLAGS_SAFE_BOOT = 2 # Safe boot mode (0 = inactive, 1 = active)
uint8 FLAGS_JAMMING_STATE_MASK = 12 # output from Jamming/Interference Monitor:
uint8 JAMMING_STATE_UNKNOWN_OR_DISABLED = 0 # unknown or feature disabled
uint8 JAMMING_STATE_OK = 4 # ok - no significant jamming
uint8 JAMMING_STATE_WARNING = 8 # interference visible but fix OK
uint8 JAMMING_STATE_CRITICAL = 12 # interference visible and no fix
uint8 FLAGS_XTAL_ABSENT = 16 # RTC XTAL is absent
# (not supported in protocol versions < 18)
uint8 reserved0 # Reserved
uint32 usedMask # Mask of Pins that are used by the Virtual Pin
# Manager
uint8[25] VP # Array of Pin Mappings for each of the 25
# Physical Pins
uint8 jamInd # CW Jamming indicator, scaled:
uint8 JAM_IND_NONE = 0 # No CW Jamming
uint8 JAM_IND_STRONG = 255 # Strong CW Jamming
uint8[2] reserved1 # Reserved
uint32 pinIrq # Mask of Pins Value using the PIO Irq
uint32 pullH # Mask of Pins Value using the PIO Pull High
# Resistor
uint32 pullL # Mask of Pins Value using the PIO Pull Low
# Resistor

View File

@@ -0,0 +1,14 @@
# MON-VER (0x0A 0x04)
#
# Receiver/Software Version
# Returned when the version is polled.
uint8 CLASS_ID = 10
uint8 MESSAGE_ID = 4
char[30] swVersion # Zero-terminated software version string.
char[10] hwVersion # Zero-terminated hardware version string.
# Start of repeated block (N times)
MonVER_Extension[] extension
# End of repeated block

View File

@@ -0,0 +1,4 @@
# see MonVER message
#
char[30] field

View File

@@ -0,0 +1,23 @@
# NAV-ATT (0x01 0x05)
# Attitude Solution
#
# This message outputs the attitude solution as roll, pitch and heading angles.
# Supported on ADR and UDR products.
#
uint8 CLASS_ID = 1
uint8 MESSAGE_ID = 5
uint32 iTOW # GPS time of week of the navigation epoch [ms]
uint8 version # Message version (0 for this version)
uint8[3] reserved0 # Reserved
int32 roll # Vehicle roll. [deg / 1e-5]
int32 pitch # Vehicle pitch. [deg / 1e-5]
int32 heading # Vehicle heading. [deg / 1e-5]
uint32 accRoll # Vehicle roll accuracy (if null, roll angle is not
# available). [deg / 1e-5]
uint32 accPitch # Vehicle pitch accuracy (if null, pitch angle is not
# available). [deg / 1e-5]
uint32 accHeading # Vehicle heading accuracy [deg / 1e-5]

View File

@@ -0,0 +1,13 @@
# NAV-CLOCK (0x01 0x22)
# Clock Solution
#
uint8 CLASS_ID = 1
uint8 MESSAGE_ID = 34
uint32 iTOW # GPS Millisecond Time of week [ms]
int32 clkB # Clock bias in nanoseconds [ns]
int32 clkD # Clock drift in nanoseconds per second [ns/s]
uint32 tAcc # Time Accuracy Estimate [ns]
uint32 fAcc # Frequency Accuracy Estimate [ps/s]

View File

@@ -0,0 +1,25 @@
# NAV-DGPS (0x01 0x31)
# DGPS Data Used for NAV
#
# This message outputs the Correction data as it has been applied to the current
# NAV Solution. See also the notes on the RTCM protocol.
#
uint8 CLASS_ID = 1
uint8 MESSAGE_ID = 49
uint32 iTOW # GPS Millisecond time of week [ms]
int32 age # Age of newest correction data [ms]
int16 baseId # DGPS Base Station ID
int16 baseHealth # DGPS Base Station Health Status
int8 numCh # Number of channels for which correction data is
# following
uint8 status # DGPS Correction Type Status
uint8 DGPS_CORRECTION_NONE = 0
uint8 DGPS_CORRECTION_PR_PRR = 1
uint16 reserved1 # Reserved
NavDGPS_SV[] sv

View File

@@ -0,0 +1,13 @@
# see message NavDGPS
uint8 svid # Satellite ID
uint8 flags # Bitmask / Channel Number and Usage:
uint8 FLAGS_CHANNEL_MASK = 15 # Bitmask for channel number, range 0..15
# Channel numbers > 15 marked as 15
uint8 FLAGS_DGPS = 16 # DGPS Used for this SV
uint16 ageC # Age of latest correction data [ms]
float32 prc # Pseudo Range Correction [m]
float32 prrc # Pseudo Range Rate Correction [m/s]

View File

@@ -0,0 +1,20 @@
# NAV-DOP (0x01 0x04)
# Dilution of precision
#
# - DOP values are dimensionless.
# - All DOP values are scaled by a factor of 100. If the unit transmits a value
# of e.g. 156, the DOP value is 1.56.
#
uint8 CLASS_ID = 1
uint8 MESSAGE_ID = 4
uint32 iTOW # GPS Millisecond Time of Week [ms]
uint16 gDOP # Geometric DOP [1 / 0.01]
uint16 pDOP # Position DOP [1 / 0.01]
uint16 tDOP # Time DOP [1 / 0.01]
uint16 vDOP # Vertical DOP [1 / 0.01]
uint16 hDOP # Horizontal DOP [1 / 0.01]
uint16 nDOP # Northing DOP [1 / 0.01]
uint16 eDOP # Easting DOP [1 / 0.01]

View File

@@ -0,0 +1,16 @@
# NAV-POSECEF (0x01 0x01)
# Position Solution in ECEF
#
# See important comments concerning validity of position given in section
# Navigation Output Filters.
#
uint8 CLASS_ID = 1
uint8 MESSAGE_ID = 1
uint32 iTOW # GPS Millisecond Time of Week [ms]
int32 ecefX # ECEF X coordinate [cm]
int32 ecefY # ECEF Y coordinate [cm]
int32 ecefZ # ECEF Z coordinate [cm]
uint32 pAcc # Position Accuracy Estimate [cm]

View File

@@ -0,0 +1,21 @@
# NAV-POSLLH (0x01 0x02)
# Geodetic Position Solution
#
# See important comments concerning validity of position given in section
# Navigation Output Filters.
# This message outputs the Geodetic position in the currently selected
# Ellipsoid. The default is the WGS84 Ellipsoid, but can be changed with the
# message CFG-DAT.
#
uint8 CLASS_ID = 1
uint8 MESSAGE_ID = 2
uint32 iTOW # GPS Millisecond Time of Week [ms]
int32 lon # Longitude [deg / 1e-7]
int32 lat # Latitude [deg / 1e-7]
int32 height # Height above Ellipsoid [mm]
int32 hMSL # Height above mean sea level [mm]
uint32 hAcc # Horizontal Accuracy Estimate [mm]
uint32 vAcc # Vertical Accuracy Estimate [mm]

View File

@@ -0,0 +1,92 @@
# NAV-PVT (0x01 0x07)
# Navigation Position Velocity Time Solution
#
# Note that during a leap second there may be more (or less) than 60 seconds in
# a minute; see the description of leap seconds for details.
#
# This message combines Position, velocity and time solution in LLH,
# including accuracy figures
#
# WARNING: For firmware version 7, this message is a different length.
#
uint8 CLASS_ID = 1
uint8 MESSAGE_ID = 7
uint32 iTOW # GPS Millisecond time of week [ms]
uint16 year # Year (UTC)
uint8 month # Month, range 1..12 (UTC)
uint8 day # Day of month, range 1..31 (UTC)
uint8 hour # Hour of day, range 0..23 (UTC)
uint8 min # Minute of hour, range 0..59 (UTC)
uint8 sec # Seconds of minute, range 0..60 (UTC)
uint8 valid # Validity flags
uint8 VALID_DATE = 1 # Valid UTC Date
uint8 VALID_TIME = 2 # Valid
uint8 VALID_FULLY_RESOLVED = 4 # UTC time of day has been fully resolved
# (no seconds uncertainty)
uint8 VALID_MAG = 8 # Valid Magnetic Declination
uint32 tAcc # time accuracy estimate [ns] (UTC)
int32 nano # fraction of a second [ns], range -1e9 .. 1e9 (UTC)
uint8 fixType # GNSS fix Type, range 0..5
uint8 FIX_TYPE_NO_FIX = 0
uint8 FIX_TYPE_DEAD_RECKONING_ONLY = 1
uint8 FIX_TYPE_2D = 2 # Signal from only 3 SVs,
# constant altitude assumed
uint8 FIX_TYPE_3D = 3
uint8 FIX_TYPE_GNSS_DEAD_RECKONING_COMBINED = 4 # GNSS + Dead reckoning
uint8 FIX_TYPE_TIME_ONLY = 5 # Time only fix (High precision
# devices)
uint8 flags # Fix Status Flags
uint8 FLAGS_GNSS_FIX_OK = 1 # i.e. within DOP & accuracy masks
uint8 FLAGS_DIFF_SOLN = 2 # DGPS used
uint8 FLAGS_PSM_MASK = 28 # Power Save Mode
uint8 PSM_OFF = 0 # PSM is off
uint8 PSM_ENABLED = 4 # Enabled (state before acquisition)
uint8 PSM_ACQUIRED = 8 # Acquisition
uint8 PSM_TRACKING = 12 # Tracking
uint8 PSM_POWER_OPTIMIZED_TRACKING = 16 # Power Optimized Tracking
uint8 PSM_INACTIVE = 20 # Inactive
uint8 FLAGS_HEAD_VEH_VALID = 32 # heading of vehicle is valid
uint8 FLAGS_CARRIER_PHASE_MASK = 192 # Carrier Phase Range Solution Status
uint8 CARRIER_PHASE_NO_SOLUTION = 0 # no carrier phase range solution
uint8 CARRIER_PHASE_FLOAT = 64 # carrier phase float solution (no fixed
# integer measurements have been used to
# calculate the solution)
uint8 CARRIER_PHASE_FIXED = 128 # fixed solution (>=1 fixed integer
# carrier phase range measurements have
# been used to calculate the solution)
uint8 flags2 # Additional Flags
uint8 FLAGS2_CONFIRMED_AVAILABLE = 32 # information about UTC Date and Time of
# Day validity confirmation is available
uint8 FLAGS2_CONFIRMED_DATE = 64 # UTC Date validity could be confirmed
uint8 FLAGS2_CONFIRMED_TIME = 128 # UTC Time of Day could be confirmed
uint8 numSV # Number of SVs used in Nav Solution
int32 lon # Longitude [deg / 1e-7]
int32 lat # Latitude [deg / 1e-7]
int32 height # Height above Ellipsoid [mm]
int32 hMSL # Height above mean sea level [mm]
uint32 hAcc # Horizontal Accuracy Estimate [mm]
uint32 vAcc # Vertical Accuracy Estimate [mm]
int32 velN # NED north velocity [mm/s]
int32 velE # NED east velocity [mm/s]
int32 velD # NED down velocity [mm/s]
int32 gSpeed # Ground Speed (2-D) [mm/s]
int32 heading # Heading of motion 2-D [deg / 1e-5]
uint32 sAcc # Speed Accuracy Estimate [mm/s]
uint32 headAcc # Heading Accuracy Estimate (both motion & vehicle)
# [deg / 1e-5]
uint16 pDOP # Position DOP [1 / 0.01]
uint8[6] reserved1 # Reserved
int32 headVeh # Heading of vehicle (2-D) [deg / 1e-5]
int16 magDec # Magnetic declination [deg / 1e-2]
uint16 magAcc # Magnetic declination accuracy [deg / 1e-2]

View File

@@ -0,0 +1,88 @@
# NAV-PVT (0x01 0x07)
# Navigation Position Velocity Time Solution Firmware version 7
#
# Note that during a leap second there may be more (or less) than 60 seconds in
# a minute; see the description of leap seconds for details.
#
# This message combines Position, velocity and time solution in LLH,
# including accuracy figures
#
# WARNING: For firmware version 7, this message is a different length.
#
uint8 CLASS_ID = 1
uint8 MESSAGE_ID = 7
uint32 iTOW # GPS Millisecond time of week [ms]
uint16 year # Year (UTC)
uint8 month # Month, range 1..12 (UTC)
uint8 day # Day of month, range 1..31 (UTC)
uint8 hour # Hour of day, range 0..23 (UTC)
uint8 min # Minute of hour, range 0..59 (UTC)
uint8 sec # Seconds of minute, range 0..60 (UTC)
uint8 valid # Validity flags
uint8 VALID_DATE = 1 # Valid UTC Date
uint8 VALID_TIME = 2 # Valid
uint8 VALID_FULLY_RESOLVED = 4 # UTC time of day has been fully resolved
# (no seconds uncertainty)
uint8 VALID_MAG = 8 # Valid Magnetic Declination
uint32 tAcc # time accuracy estimate [ns] (UTC)
int32 nano # fraction of a second [ns], range -1e9 .. 1e9 (UTC)
uint8 fixType # GNSS fix Type, range 0..5
uint8 FIX_TYPE_NO_FIX = 0
uint8 FIX_TYPE_DEAD_RECKONING_ONLY = 1
uint8 FIX_TYPE_2D = 2 # Signal from only 3 SVs,
# constant altitude assumed
uint8 FIX_TYPE_3D = 3
uint8 FIX_TYPE_GNSS_DEAD_RECKONING_COMBINED = 4 # GNSS + Dead reckoning
uint8 FIX_TYPE_TIME_ONLY = 5 # Time only fix (High precision
# devices)
uint8 flags # Fix Status Flags
uint8 FLAGS_GNSS_FIX_OK = 1 # i.e. within DOP & accuracy masks
uint8 FLAGS_DIFF_SOLN = 2 # DGPS used
uint8 FLAGS_PSM_MASK = 28 # Power Save Mode
uint8 PSM_OFF = 0 # PSM is off
uint8 PSM_ENABLED = 4 # Enabled (state before acquisition)
uint8 PSM_ACQUIRED = 8 # Acquisition
uint8 PSM_TRACKING = 12 # Tracking
uint8 PSM_POWER_OPTIMIZED_TRACKING = 16 # Power Optimized Tracking
uint8 PSM_INACTIVE = 20 # Inactive
uint8 FLAGS_HEAD_VEH_VALID = 32 # heading of vehicle is valid
uint8 FLAGS_CARRIER_PHASE_MASK = 192 # Carrier Phase Range Solution Status
uint8 CARRIER_PHASE_NO_SOLUTION = 0 # no carrier phase range solution
uint8 CARRIER_PHASE_FLOAT = 64 # carrier phase float solution (no fixed
# integer measurements have been used to
# calculate the solution)
uint8 CARRIER_PHASE_FIXED = 128 # fixed solution (>=1 fixed integer
# carrier phase range measurements have
# been used to calculate the solution)
uint8 flags2 # Additional Flags
uint8 FLAGS2_CONFIRMED_AVAILABLE = 32 # information about UTC Date and Time of
# Day validity confirmation is available
uint8 FLAGS2_CONFIRMED_DATE = 64 # UTC Date validity could be confirmed
uint8 FLAGS2_CONFIRMED_TIME = 128 # UTC Time of Day could be confirmed
uint8 numSV # Number of SVs used in Nav Solution
int32 lon # Longitude [deg / 1e-7]
int32 lat # Latitude [deg / 1e-7]
int32 height # Height above Ellipsoid [mm]
int32 hMSL # Height above mean sea level [mm]
uint32 hAcc # Horizontal Accuracy Estimate [mm]
uint32 vAcc # Vertical Accuracy Estimate [mm]
int32 velN # NED north velocity [mm/s]
int32 velE # NED east velocity [mm/s]
int32 velD # NED down velocity [mm/s]
int32 gSpeed # Ground Speed (2-D) [mm/s]
int32 heading # Heading of motion 2-D [deg / 1e-5]
uint32 sAcc # Speed Accuracy Estimate [mm/s]
uint32 headAcc # Heading Accuracy Estimate (both motion & vehicle)
# [deg / 1e-5]
uint16 pDOP # Position DOP [1 / 0.01]
uint8[6] reserved1 # Reserved

View File

@@ -0,0 +1,85 @@
# NAV-RELPOSNED (0x01 0x3C)
# Relative Positioning Information in NED frame
#
# The NED frame is defined as the local topological system at the reference
# station. The relative position vector components in this message, along with
# their associated accuracies, are given in that local topological system
# This message contains the relative position vector from the Reference Station
# to the Rover, including accuracy figures, in the local topological system
# defined at the reference station
#
# Supported on:
# - u-blox 8 / u-blox M8 from protocol version 20 up to version 23.01 (only
# with High Precision GNSS products)
#
uint8 CLASS_ID = 1
uint8 MESSAGE_ID = 60
uint8 version # Message version (0x00 for this version)
uint8 reserved0 # Reserved
uint16 refStationId # Reference Station ID. Must be in the range
# 0..4095
uint32 iTow # GPS time of week of the navigation epoch
# [ms]
int32 relPosN # North component of relative position vector
# [cm]
int32 relPosE # East component of relative position vector
# [cm]
int32 relPosD # Down component of relative position vector
# [cm]
int8 relPosHPN # High-precision North component of relative
# position vector. [0.1 mm]
# Must be in the range -99 to +99.
# The full North component of the relative
# position vector, in units of cm, is given by
# relPosN + (relPosHPN * 1e-2)
int8 relPosHPE # High-precision East component of relative
# position vector. [0.1 mm]
# Must be in the range -99 to +99.
# The full East component of the relative
# position vector, in units of cm, is given by
# relPosE + (relPosHPE * 1e-2)
int8 relPosHPD # High-precision Down component of relative
# position vector. [0.1 mm]
# Must be in the range -99 to +99.
# The full Down component of the relative
# position vector, in units of cm, is given by
# relPosD + (relPosHPD * 1e-2)
uint8 reserved1 # Reserved
uint32 accN # Accuracy of relative position North
# component [0.1 mm]
uint32 accE # Accuracy of relative position East component
# [0.1 mm]
uint32 accD # Accuracy of relative position Down component
# [0.1 mm]
uint32 flags
uint32 FLAGS_GNSS_FIX_OK = 1 # A valid fix (i.e within DOP & accuracy
# masks)
uint32 FLAGS_DIFF_SOLN = 2 # Set if differential corrections were applied
uint32 FLAGS_REL_POS_VALID = 4 # Set if relative position components and
# accuracies are valid
uint32 FLAGS_CARR_SOLN_MASK = 24 # Carrier phase range solution status:
uint32 FLAGS_CARR_SOLN_NONE = 0 # No carrier phase range solution
uint32 FLAGS_CARR_SOLN_FLOAT = 8 # Float solution. No fixed integer carrier
# phase measurements have been used to
# calculate the solution
uint32 FLAGS_CARR_SOLN_FIXED = 16 # Fixed solution. One or more fixed
# integer carrier phase range measurements
# have been used to calculate the solution
uint32 FLAGS_IS_MOVING = 32 # if the receiver is operating in moving
# baseline mode (not supported in protocol
# versions less than 20.3)
uint32 FLAGS_REF_POS_MISS = 64 # Set if extrapolated reference position was
# used to compute moving baseline solution
# this epoch (not supported in protocol
# versions less than 20.3)
uint32 FLAGS_REF_OBS_MISS = 128 # Set if extrapolated reference observations
# were used to compute moving baseline
# solution this epoch (not supported in
# protocol versions less than 20.3)

View File

@@ -0,0 +1,18 @@
# NAV-SAT (0x01 0x35)
# Satellite Information
#
# This message displays information about SVs which are either known to be
# visible or currently tracked by the receiver.
#
uint8 CLASS_ID = 1
uint8 MESSAGE_ID = 53
uint32 iTOW # GPS time of week of the navigation epoch. [ms]
uint8 version # Message version (1 for this version)
uint8 numSvs # Number of satellites
uint8[2] reserved0 # Reserved
# start of repeated block (numSvs times)
NavSAT_SV[] sv
# end of repeated block

View File

@@ -0,0 +1,80 @@
# see NAV-SAT message
#
uint8 gnssId # GNSS identifier
uint8 svId # Satellite identifier
uint8 cno # Carrier to noise ratio (signal strength) ]dBHz
int8 elev # Elevation (range: +/-90), unknown if out of range [deg]
int16 azim # Azimuth (range 0-360), unknown if elevation is out of range
# [deg]
int16 prRes # Pseudo range residual [0.1 m]
uint32 flags # Bitmask
uint32 FLAGS_QUALITY_IND_MASK = 7 # Signal quality indicator:
uint8 QUALITY_IND_NO_SIGNAL = 0 # no signal
uint8 QUALITY_IND_SEARCHING_SIGNAL = 1 # searching signal
uint8 QUALITY_IND_SIGNAL_ACQUIRED = 2 # signal acquired
uint8 QUALITY_IND_SIGNAL_DETECTED_BUT_UNUSABLE = 3 # signal detected but
# unusable
uint8 QUALITY_IND_CODE_LOCKED_AND_TIME_SYNC = 4 # code locked and time
# synchronized
uint8 QUALITY_IND_CODE_AND_CARR_LOCK_AND_TIME_SYNC1 = 5 # code and carrier
# locked and time
# synchronized,
# quality = 1
uint8 QUALITY_IND_CODE_AND_CARR_LOCK_AND_TIME_SYNC2 = 6 # code and carrier
# locked and time
# synchronized,
# quality = 2
uint8 QUALITY_IND_CODE_AND_CARR_LOCK_AND_TIME_SYNC3 = 7 # code and carrier
# locked and time
# synchronized,
# quality = 3
# Note: Since IMES signals are not time synchronized, a channel tracking an IMES
# signal can never reach a quality indicator value of higher than 3.
uint32 FLAGS_SV_USED = 8 # whether SV is currently being
# used for navigation
uint32 FLAGS_HEALTH_MASK = 48 # SV health flag:
uint32 HEALTH_UNKNOWN = 0 # unknown
uint32 HEALTH_HEALTHY = 1 # healthy
uint32 HEALTH_UNHEALTHY = 2 # unhealthy
uint32 FLAGS_DIFF_CORR = 64 # whether differential correction
# data is available for this SV
uint32 FLAGS_SMOOTHED = 128 # whether carrier smoothed
# pseudorange used
uint32 FLAGS_ORBIT_SOURCE_MASK = 1792 # Orbit source:
uint32 ORBIT_SOURCE_UNAVAILABLE = 0 # no orbit information is
# available for this SV
uint32 ORBIT_SOURCE_EPH = 256 # ephemeris is used
uint32 ORBIT_SOURCE_ALM = 512 # almanac is used
uint32 ORBIT_SOURCE_ASSIST_OFFLINE = 768 # AssistNow Offline orbit is
# used
uint32 ORBIT_SOURCE_ASSIST_AUTONOMOUS = 1024 # AssistNow Autonomous orbit is
# used
uint32 ORBIT_SOURCE_OTHER1 = 1280 # other orbit information is
# used
uint32 ORBIT_SOURCE_OTHER2 = 1536 # other orbit information is
# used
uint32 ORBIT_SOURCE_OTHER3 = 1792 # other orbit information is
# used
uint32 FLAGS_EPH_AVAIL = 2048 # whether ephemeris is available
# for this SV
uint32 FLAGS_ALM_AVAIL = 4096 # whether almanac is available for
# this SV
uint32 FLAGS_ANO_AVAIL = 8192 # whether AssistNow Offline data
# is available for this SV
uint32 FLAGS_AOP_AVAIL = 16384 # whether AssistNow Autonomous
# data is available for this SV
uint32 FLAGS_SBAS_CORR_USED = 65536 # whether SBAS corrections have
# been used for this SV
uint32 FLAGS_RTCM_CORR_USED = 131072 # whether RTCM corrections have
# been used for this SV
uint32 FLAGS_PR_CORR_USED = 1048576 # whether Pseudorange corrections
# have been used for this SV
uint32 FLAGS_CR_CORR_USED = 2097152 # whether Carrier range
# corrections have been used for
# this SV
uint32 FLAGS_DO_CORR_USED = 4194304 # whether Range rate (Doppler)
# corrections have been used for
# this SV

View File

@@ -0,0 +1,37 @@
# NAV-SBAS (0x01 0x32)
# SBAS Status Data
#
# This message outputs the status of the SBAS sub system
#
uint8 CLASS_ID = 1
uint8 MESSAGE_ID = 50
uint32 iTOW # GPS Millisecond time of week [ms]
uint8 geo # PRN Number of the GEO where correction and integrity
# data is used from
uint8 mode # SBAS Mode
uint8 MODE_DISABLED = 0
uint8 MODE_ENABLED_INTEGRITY = 1
uint8 MODE_ENABLED_TESTMODE = 3
int8 sys # SBAS System (WAAS/EGNOS/...)
int8 SYS_UNKNOWN = -1
int8 SYS_WAAS = 0
int8 SYS_EGNOS = 1
int8 SYS_MSAS = 2
int8 SYS_GAGAN = 3
int8 SYS_GPS = 16
uint8 service # SBAS Services available
uint8 SERVICE_RANGING = 1
uint8 SERVICE_CORRECTIONS = 2
uint8 SERVICE_INTEGRITY = 4
uint8 SERVICE_TESTMODE = 8
uint8 cnt # Number of SV data following
uint8[3] reserved0 # Reserved
NavSBAS_SV[] sv

View File

@@ -0,0 +1,12 @@
# see message NavSBAS
#
uint8 svid # SV Id
uint8 flags # Flags for this SV
uint8 udre # Monitoring status
uint8 svSys # System (WAAS/EGNOS/...), same as SYS
uint8 svService # Services available, same as SERVICE
uint8 reserved1 # Reserved
int16 prc # Pseudo Range correction in [cm]
uint16 reserved2 # Reserved
int16 ic # Ionosphere correction in [cm]

View File

@@ -0,0 +1,43 @@
# NAV-SOL (0x01 0x06)
# Navigation Solution Information
#
# This message combines Position, velocity and time solution in ECEF, including
# accuracy figures
# This message has only been retained for backwards compatibility; users are
# recommended to use the UBX-NAV-PVT message in preference.
#
uint8 CLASS_ID = 1
uint8 MESSAGE_ID = 6
uint32 iTOW # GPS Millisecond time of week [ms]
int32 fTOW # Fractional Nanoseconds remainder of rounded
# ms above, range -500000 .. 500000 [ns]
int16 week # GPS week (GPS time)
uint8 gpsFix # GPSfix Type, range 0..5
uint8 GPS_NO_FIX = 0
uint8 GPS_DEAD_RECKONING_ONLY = 1
uint8 GPS_2D_FIX = 2
uint8 GPS_3D_FIX = 3
uint8 GPS_GPS_DEAD_RECKONING_COMBINED = 4
uint8 GPS_TIME_ONLY_FIX = 5
uint8 flags # Fix Status Flags
uint8 FLAGS_GPS_FIX_OK = 1 # Fix within limits i.e. within DOP & ACC Masks
uint8 FLAGS_DIFF_SOLN = 2 # DGPS used
uint8 FLAGS_WKNSET = 4 # Week Number valid
uint8 FLAGS_TOWSET = 8 # Time of Week valid
int32 ecefX # ECEF X coordinate [cm]
int32 ecefY # ECEF Y coordinate [cm]
int32 ecefZ # ECEF Z coordinate [cm]
uint32 pAcc # 3D Position Accuracy Estimate [cm]
int32 ecefVX # ECEF X velocity [cm/s]
int32 ecefVY # ECEF Y velocity [cm/s]
int32 ecefVZ # ECEF Z velocity [cm/s]
uint32 sAcc # Speed Accuracy Estimate [cm/s]
uint16 pDOP # Position DOP [1 / 0.01]
uint8 reserved1 # Reserved
uint8 numSV # Number of SVs used in Nav Solution
uint32 reserved2 # Reserved

View File

@@ -0,0 +1,65 @@
# NAV-STATUS (0x01 0x03)
# Receiver Navigation Status
#
# See important comments concerning validity of position and velocity given in
# section Navigation Output Filters.
#
uint8 CLASS_ID = 1
uint8 MESSAGE_ID = 3
uint32 iTOW # GPS Millisecond time of week [ms]
uint8 gpsFix # GPSfix Type, this value does not qualify a fix as
# valid and within the limits. See note on flag gpsFixOk
# below
uint8 GPS_NO_FIX = 0
uint8 GPS_DEAD_RECKONING_ONLY = 1
uint8 GPS_2D_FIX = 2
uint8 GPS_3D_FIX = 3
uint8 GPS_GPS_DEAD_RECKONING_COMBINED = 4
uint8 GPS_TIME_ONLY_FIX = 5
uint8 flags # Navigation Status Flags
uint8 FLAGS_GPS_FIX_OK = 1 # position & velocity valid & within DOP & ACC
# Masks
uint8 FLAGS_DIFF_SOLN = 2 # Differential corrections were applied
uint8 FLAGS_WKNSET = 4 # Week Number valid
uint8 FLAGS_TOWSET = 8 # Time of Week valid
uint8 fixStat # Fix Status Information
uint8 FIX_STAT_DIFF_CORR_MASK = 1 # 1 = differential corrections available
# map matching status:
uint8 FIX_STAT_MAP_MATCHING_MASK = 192
uint8 MAP_MATCHING_NONE = 0 # none
uint8 MAP_MATCHING_VALID = 64 # valid but not used, i.e. map matching data
# was received, but was too old
uint8 MAP_MATCHING_USED = 128 # valid and used, map matching data was applied
uint8 MAP_MATCHING_DR = 192 # valid and used, map matching data was
# applied. In case of sensor unavailability map
# matching data enables dead reckoning.
# This requires map matched latitude/longitude
# or heading data.
uint8 flags2 # further information about navigation output
# power safe mode state (Only for FW version >= 7.01; undefined otherwise)
uint8 FLAGS2_PSM_STATE_MASK = 3
uint8 PSM_STATE_ACQUISITION = 0 # ACQUISITION
# [or when psm disabled]
uint8 PSM_STATE_TRACKING = 1 # TRACKING
uint8 PSM_STATE_POWER_OPTIMIZED_TRACKING = 2 # POWER OPTIMIZED TRACKING
uint8 PSM_STATE_INACTIVE = 3 # INACTIVE
# Note that the spoofing state value only reflects the detector state for the
# current navigation epoch. As spoofing can be detected most easily at the
# transition from real signal to spoofing signal, this is also where the
# detector is triggered the most. I.e. a value of 1 - No spoofing indicated does
# not mean that the receiver is not spoofed, it #simply states that the detector
# was not triggered in this epoch.
uint8 FLAGS2_SPOOF_DET_STATE_MASK = 24
uint8 SPOOF_DET_STATE_UNKNOWN = 0 # Unknown or deactivated
uint8 SPOOF_DET_STATE_NONE = 8 # No spoofing indicated
uint8 SPOOF_DET_STATE_SPOOFING = 16 # Spoofing indicated
uint8 SPOOF_DET_STATE_MULTIPLE = 24 # Multiple spoofing indication
uint32 ttff # Time to first fix (millisecond time tag) [ms]
uint32 msss # Milliseconds since Startup / Reset [ms]

View File

@@ -0,0 +1,51 @@
# NAV-SVIN (0x01 0x3B)
# Survey-in data
#
# This message contains information about survey-in parameters.
# Supported on:
# - u-blox 8 / u-blox M8 with protocol version 20 (only with High Precision
# GNSS products)
uint8 CLASS_ID = 1
uint8 MESSAGE_ID = 59
uint8 version # Message version (0x00 for this version)
uint8[3] reserved0 # Reserved
uint32 iTOW # GPS time of week of the navigation epoch [ms]
uint32 dur # Passed survey-in observation time [s]
int32 meanX # Current survey-in mean position ECEF X coordinate [cm]
int32 meanY # Current survey-in mean position ECEF Y coordinate [cm]
int32 meanZ # Current survey-in mean position ECEF Z coordinate [cm]
int8 meanXHP # Current high-precision survey-in mean position
# ECEF X coordinate. 0.1_mm
# Must be in the range -99..+99.
# The current survey-in mean position ECEF X
# coordinate, in units of cm, is given by
# meanX + (0.01 * meanXHP)
int8 meanYHP # Current high-precision survey-in mean position
# ECEF Y coordinate. [0.1 mm]
# Must be in the range -99..+99.
# The current survey-in mean position ECEF Y
# coordinate, in units of cm, is given by
# meanY + (0.01 * meanYHP)
int8 meanZHP # Current high-precision survey-in mean position
# ECEF Z coordinate. [0.1 mm]
# Must be in the range -99..+99.
# The current survey-in mean position ECEF Z
# coordinate, in units of cm, is given by
# meanZ + (0.01 * meanZHP)
uint8 reserved1 # Reserved
uint32 meanAcc # Current survey-in mean position accuracy [0.1 mm]
uint32 obs # Number of position observations used during survey-in
uint8 valid # Survey-in position validity flag, 1 = valid
# otherwise 0
uint8 active # Survey-in in progress flag, 1 = in-progress
# otherwise 0
uint8[2] reserved3 # Reserved

View File

@@ -0,0 +1,22 @@
# NAV-SVINFO (0x01 0x30)
# Space Vehicle Information
#
uint8 CLASS_ID = 1
uint8 MESSAGE_ID = 48
uint32 iTOW # GPS Millisecond time of week [ms]
uint8 numCh # Number of channels
uint8 globalFlags # Bitmask
# Chip Hardware generation flags
uint8 CHIPGEN_ANTARIS = 0 # Antaris, Antaris 4
uint8 CHIPGEN_UBLOX5 = 1 # u-blox 5
uint8 CHIPGEN_UBLOX6 = 2 # u-blox 6
uint8 CHIPGEN_UBLOX7 = 3 # u-blox 7
uint8 CHIPGEN_UBLOX8 = 4 # u-blox 8 / u-blox M8
uint16 reserved2 # Reserved
NavSVINFO_SV[] sv

View File

@@ -0,0 +1,41 @@
# see message NavSVINFO
#
uint8 chn # Channel number, 255 for SVs not assigned to a channel
uint8 svid # Satellite ID
uint8 flags # Bitmask
uint8 FLAGS_SV_USED = 1 # SV is used for navigation
uint8 FLAGS_DIFF_CORR = 2 # Differential correction data
# is available for this SV
uint8 FLAGS_ORBIT_AVAIL = 4 # Orbit information is available for
# this SV (Ephemeris or Almanach)
uint8 FLAGS_ORBIT_EPH = 8 # Orbit information is Ephemeris
uint8 FLAGS_UNHEALTHY = 16 # SV is unhealthy / shall not be
# used
uint8 FLAGS_ORBIT_ALM = 32 # Orbit information is Almanac Plus
uint8 FLAGS_ORBIT_AOP = 64 # Orbit information is AssistNow
# Autonomous
uint8 FLAGS_SMOOTHED = 128 # Carrier smoothed pseudorange used
uint8 quality # Bitfield
# qualityInd: Signal Quality indicator (range 0..7). The following list shows
# the meaning of the different QI values:
# Note: Since IMES signals are not time synchronized, a channel tracking an IMES
# signal can never reach a quality indicator value of higher than 3.
uint8 QUALITY_IDLE = 0 # This channel is idle
uint8 QUALITY_SEARCHING = 1 # Channel is searching
uint8 QUALITY_ACQUIRED = 2 # Signal acquired
uint8 QUALITY_DETECTED = 3 # Signal detected but unusable
uint8 QUALITY_CODE_LOCK = 4 # Code Lock on Signal
uint8 QUALITY_CODE_AND_CARRIER_LOCKED1 = 5 # Code and Carrier locked
# and time synchronized
uint8 QUALITY_CODE_AND_CARRIER_LOCKED2 = 6 # Code and Carrier locked
# and time synchronized
uint8 QUALITY_CODE_AND_CARRIER_LOCKED3 = 7 # Code and Carrier locked
# and time synchronized
uint8 cno # Carrier to Noise Ratio (Signal Strength) [dBHz]
int8 elev # Elevation in integer degrees [deg]
int16 azim # Azimuth in integer degrees [deg]
int32 prRes # Pseudo range residual in centimetres [cm]

View File

@@ -0,0 +1,20 @@
# NAV-TIMEGPS (0x01 0x20)
# GPS Time Solution
#
uint8 CLASS_ID = 1
uint8 MESSAGE_ID = 32
uint32 iTOW # GPS Millisecond time of week [ms]
int32 fTOW # Fractional Nanoseconds remainder of rounded
# ms above, range -500000 .. 500000 [ns]
int16 week # GPS week (GPS time)
int8 leapS # Leap Seconds (GPS-UTC) [s]
uint8 valid # Validity Flags
uint8 VALID_TOW = 1 # Valid Time of Week
uint8 VALID_WEEK = 2 # Valid Week Number
uint8 VALID_LEAP_S = 4 # Valid Leap Seconds
uint32 tAcc # Time Accuracy Estimate [ns]

View File

@@ -0,0 +1,35 @@
# NAV-TIMEUTC (0x01 0x21)
# UTC Time Solution
#
uint8 CLASS_ID = 1
uint8 MESSAGE_ID = 33
uint32 iTOW # GPS Millisecond time of week [ms]
uint32 tAcc # Time Accuracy Estimate [ns]
int32 nano # Fraction of second, range -1e9 .. 1e9 (UTC) [ns]
uint16 year # Year, range 1999..2099 (UTC) [y]
uint8 month # Month, range 1..12 (UTC) [month]
uint8 day # Day of Month, range 1..31 (UTC) [d]
uint8 hour # Hour of Day, range 0..23 (UTC) [h]
uint8 min # Minute of Hour, range 0..59 (UTC) [min]
uint8 sec # Seconds of Minute, range 0..60 (UTC) [s] (60 for
# leap second)
uint8 valid # Validity Flags
uint8 VALID_TOW = 1 # Valid Time of Week
uint8 VALID_WKN = 2 # Valid Week Number
uint8 VALID_UTC = 4 # Valid Leap Seconds, i.e. Leap Seconds already known
uint8 VALID_UTC_STANDARD_MASK = 240 # UTC standard Identifier Bit mask:
uint8 UTC_STANDARD_NOT_AVAILABLE = 0 # Information not available
uint8 UTC_STANDARD_CRL = 16 # Communications Research Labratory
uint8 UTC_STANDARD_NIST = 32 # National Institute of Standards and
# Technology (NIST)
uint8 UTC_STANDARD_USNO = 48 # U.S. Naval Observatory (USNO)
uint8 UTC_STANDARD_BIPM = 64 # International Bureau of Weights and
# Measures (BIPM)
uint8 UTC_STANDARD_EL = 80 # European Laboratory (tbd)
uint8 UTC_STANDARD_SU = 96 # Former Soviet Union (SU)
uint8 UTC_STANDARD_NTSC = 112 # National Time Service Center, China
uint8 UTC_STANDARD_UNKNOWN = 240

View File

@@ -0,0 +1,16 @@
# NAV-VELECEF (0x01 0x11)
# Velocity Solution in ECEF
#
# See important comments concerning validity of velocity given in section
# Navigation Output Filters.
#
uint8 CLASS_ID = 1
uint8 MESSAGE_ID = 17
uint32 iTOW # GPS Millisecond time of week [ms]
int32 ecefVX # ECEF X velocity [cm/s]
int32 ecefVY # ECEF Y velocity [cm/s]
int32 ecefVZ # ECEF Z velocity [cm/s]
uint32 sAcc # Speed Accuracy Estimate [cm/s]

View File

@@ -0,0 +1,20 @@
# NAV-VELNED (0x01 0x12)
# Velocity Solution in NED
#
# See important comments concerning validity of velocity given in section
# Navigation Output Filters.
#
uint8 CLASS_ID = 1
uint8 MESSAGE_ID = 18
uint32 iTOW # GPS Millisecond time of week [ms]
int32 velN # NED north velocity [cm/s]
int32 velE # NED east velocity [cm/s]
int32 velD # NED down velocity [cm/s]
uint32 speed # Speed (3-D) [cm/s]
uint32 gSpeed # Ground Speed (2-D) [cm/s]
int32 heading # Heading of motion 2-D [deg / 1e-5]
uint32 sAcc # Speed Accuracy Estimate [cm/s]
uint32 cAcc # Course / Heading Accuracy Estimate [deg / 1e-5]

View File

@@ -0,0 +1,27 @@
# RXM-ALM (0x02 0x30)
# GPS Aiding Almanach Input/Output Message
#
# This message is provided considered obsolete, please use AID-ALM instead!
# - If the WEEK Value is 0, DWRD0 to DWRD7 are not sent as the almanach is not
# available for the given SV.
# - DWORD0 to DWORD7 contain the 8 words following the Hand-Over Word ( HOW )
# from the GPS navigation message, either pages 1 to 24 of sub-frame 5 or
# pages 2 to 10 of subframe 4. See IS-GPS-200 for a full description of the
# contents of the Almanac pages.
# - In DWORD0 to DWORD7, the parity bits have been removed, and the 24 bits of
# data are located in Bits 0 to 23. Bits 24 to 31 shall be ignored.
# - Example: Parameter e (Eccentricity) from Almanach Subframe 4/5, Word 3,
# Bits 69-84 within the subframe can be found in DWRD0, Bits 15-0 whereas
# Bit 0 is the LSB.
#
uint8 CLASS_ID = 2
uint8 MESSAGE_ID = 48
uint32 svid # SV ID for which this Almanach Data is
# (Valid Range: 1 .. 32 or 51, 56, 63).
uint32 week # Issue Date of Almanach (GPS week number)
# Start of optional block
uint32[] dwrd # Almanach Words
# End of optional block

View File

@@ -0,0 +1,27 @@
# RXM-EPH (0x02 0x31)
# GPS Aiding Ephemeris Input/Output Message
#
# This message is provided considered obsolete, please use AID-EPH instead!
# - SF1D0 to SF3D7 is only sent if ephemeris is available for this SV. If not,
# the payload may be reduced to 8 Bytes, or all bytes are set to zero,
# indicating that this SV Number does not have valid ephemeris for the moment.
# - SF1D0 to SF3D7 contain the 24 words following the Hand-Over Word ( HOW )
# from the GPS navigation message, subframes 1 to 3. See IS-GPS-200 for a
# full description of the contents of the Subframes.
# - In SF1D0 to SF3D7, the parity bits have been removed, and the 24 bits of
# data are located in Bits 0 to 23. Bits 24 to 31 shall be ignored.
#
uint8 CLASS_ID = 2
uint8 MESSAGE_ID = 49
uint32 svid # SV ID for which this ephemeris data is (Valid Range: 1 .. 32).
uint32 how # Hand-Over Word of first Subframe. This is
# required if data is sent to the receiver.
# 0 indicates that no Ephemeris Data is following.
# Start of optional block
uint32[] sf1d # Subframe 1 Words 3..10 (SF1D0..SF1D7)
uint32[] sf2d # Subframe 2 Words 3..10 (SF2D0..SF2D7)
uint32[] sf3d # Subframe 3 Words 3..10 (SF3D0..SF3D7)
# End of optional block

View File

@@ -0,0 +1,21 @@
# RXM-RAW (0x02 0x10)
# Raw Measurement Data
#
# Supported up to ublox 7 firmware. See RxmRAWX for ublox 8
# This message contains all information needed to be able to generate a RINEX
# observation file.
# This message outputs pseudorange, doppler and carrier phase measurements for
# GPS satellites once signals have been synchronised. No other GNSS types are
# currently supported.
#
uint8 CLASS_ID = 2
uint8 MESSAGE_ID = 16
int32 rcvTOW # Measurement time of week in receiver local time [s]
int16 week # Measurement week number in receiver local time [weeks]
uint8 numSV # # of satellites following
uint8 reserved1 # Reserved
RxmRAW_SV[] sv # numSV times

View File

@@ -0,0 +1,39 @@
# RXM-RAWX (0x02 0x15)
# Multi-GNSS Raw Measurement Data
#
# This message contains the information needed to be able to generate a RINEX 3
# multi-GNSS observation file.
# This message contains pseudorange, Doppler, carrier phase, phase lock and
# signal quality information for GNSS satellites once signals have been
# synchronized. This message supports all active GNSS.
#
uint8 CLASS_ID = 2
uint8 MESSAGE_ID = 21
float64 rcvTOW # Measurement time of week in receiver local time [s]
# approximately aligned to the GPS time system. The
# receiver local time of week number and leap second
# information can be used to translate the time to other
# time systems. More information about the difference in
# time systems can be found in RINEX 3 documentation.
# For a receiver operating in GLONASS only mode, UTC
# time can be determined by subtracting the leapS field
# from GPS time regardless of whether the GPS leap
# seconds are valid.
uint16 week # GPS week number in receiver local time. [weeks]
int8 leapS # GPS leap seconds (GPS-UTC). [s]
# This field represents the receiver's best knowledge of
# the leap seconds offset. A flag is given in the
# recStat bitfield to indicate if the leap seconds
# are known.
uint8 numMeas # # of measurements to follow
uint8 recStat # Receiver tracking status bitfield
uint8 REC_STAT_LEAP_SEC = 1 # Leap seconds have been determined
uint8 REC_STAT_CLK_RESET = 2 # Clock reset applied. Typically the receiver
# clock is changed in increments of integer
# milliseconds.
uint8 version # Message version (0x01 for this version).
uint8[2] reserved1 # Reserved
RxmRAWX_Meas[] meas

View File

@@ -0,0 +1,42 @@
# see message RxmRAWX
#
float64 prMes # Pseudorange measurement [m]. GLONASS inter frequency
# channel delays are compensated with an internal
# calibration table.
float64 cpMes # Carrier phase measurement [L1 cycles]. The carrier
# phase initial ambiguity is initialized using an
# approximate value to make the magnitude of
# the phase close to the pseudorange
# measurement. Clock resets are applied to both
# phase and code measurements in accordance
# with the RINEX specification.
float32 doMes # Doppler measurement [Hz] (positive sign for
# approaching satellites)
uint8 gnssId # GNSS identifier (see CfgGNSS for constants)
uint8 svId # Satellite identifier (see Satellite Numbering)
uint8 reserved0 # Reserved
uint8 freqId # Only used for GLONASS: This is the frequency
# slot + 7 (range from 0 to 13)
uint16 locktime # Carrier phase locktime counter [ms]
# (maximum 64500 ms)
int8 cno # Carrier-to-noise density ratio (signal strength)
# [dB-Hz]
uint8 prStdev # Estimated pseudorange measurement standard
# deviation [m / 0.01*2^n]
uint8 cpStdev # Estimated carrier phase measurement standard
# deviation (note a raw value of 0x0F indicates the
# value is invalid) [cycles / 0.004]
uint8 doStdev # Estimated Doppler measurement standard deviation
# [Hz / 0.002*2^n]
uint8 trkStat # Tracking status bitfield
uint8 TRK_STAT_PR_VALID = 1 # Pseudorange valid
uint8 TRK_STAT_CP_VALID = 2 # Carrier phase valid
uint8 TRK_STAT_HALF_CYC = 4 # Half cycle valid
uint8 TRK_STAT_SUB_HALF_CYC = 8 # Half cycle subtracted from phase
uint8 reserved1 # Reserved

View File

@@ -0,0 +1,15 @@
# see message RxmRAW
#
float64 cpMes # Carrier phase measurement [L1 cycles]
float64 prMes # Pseudorange measurement [m]
float32 doMes # Doppler measurement [Hz]
uint8 sv # Space Vehicle Number
int8 mesQI # Nav Measurements Quality Indicator
# >=4 : PR+DO OK
# >=5 : PR+DO+CP OK
# <6 : likely loss of carrier lock in previous
# interval
int8 cno # Signal strength C/No. [dbHz]
uint8 lli # Loss of lock indicator (RINEX definition)

View File

@@ -0,0 +1,21 @@
# RXM-RTCM (0x02 0x32)
# RTCM input status
#
# Output upon processing of an RTCM input message
# Supported on:
# - u-blox 8 / u-blox M8 from protocol version 20.01 up to version 23.01
#
uint8 CLASS_ID = 2
uint8 MESSAGE_ID = 50
uint8 version # Message version (0x02 for this version)
uint8 flags # RTCM input status flags
uint8 FLAGS_CRC_FAILED = 1 # 0 when RTCM message received and passed CRC
# check, 1 when failed in which case refStation
# and msgType might be corrupted and misleading
uint8[2] reserved0 # Reserved
uint16 refStation # Reference station ID
uint16 msgType # Message type

View File

@@ -0,0 +1,24 @@
# RXM-SFRB (0x02 0x11)
# Subframe Buffer
#
# The content of one single subframe buffer
# For GPS satellites, the 10 dwrd values contain the parity checked subframe
# data for 10 Words. Each dwrd has 24 Bits with valid data (Bits 23 to 0). The
# remaining 8 bits (31 to 24) have an undefined value. The direction within the
# Word is that the higher order bits are received from the SV first. Example:
# The Preamble can be found in dwrd[0], at bit position 23 down to 16. For more
# details on the data format please refer to the ICD-GPS-200C
# Interface document.
# For SBAS satellites, the 250 Bit message block can be found in dwrd[0] to
# dwrd[6] for the first 224 bits. The remaining 26 bits are in dwrd[7], whereas
# Bits 25 and 24 are the last two data bits, and Bits 23 down to 0 are the
# parity bits. For more information on SBAS data format, please refer to
# RTCA/DO-229C (MOPS), Appendix A.
#
uint8 CLASS_ID = 2
uint8 MESSAGE_ID = 17
uint8 chn # Channel Number
uint8 svid # ID of Satellite transmitting Subframe
uint32[10] dwrd # Words of Data

View File

@@ -0,0 +1,28 @@
# RXM-SFRB (0x02 0x13)
# Subframe Buffer
#
# This message reports a complete subframe of broadcast navigation data decoded
# from a single signal. The number of data words reported in each message
# depends on the nature of the signal. See the section on Broadcast Navigation
# Data for further details.
#
uint8 CLASS_ID = 2
uint8 MESSAGE_ID = 19
uint8 gnssId # GNSS identifier (see Cfg GNSS for constants)
uint8 svId # Satellite identifier within corresponding GNSS system
uint8 reserved0 # Reserved
uint8 freqId # Only used for GLONASS: This is the frequency
# slot + 7 (range from 0 to 13)
uint8 numWords # The number of data words contained in this message (up
# to 10, for currently supported signals)
uint8 chn # The tracking channel number the message was received
# on
uint8 version # Message version, (0x02 for this version)
uint8 reserved1 # Reserved
# Start of repeated block (numWords times)
uint32[] dwrd # The data words
# End of repeated block

View File

@@ -0,0 +1,18 @@
# RXM-SVSI (0x02 0x20)
# SV Status Info
#
# Status of the receiver manager knowledge about GPS Orbit Validity
#
# This message has only been retained for backwards compatibility; users are
# recommended to use the UBX-NAV-ORB message in preference.
uint8 CLASS_ID = 2
uint8 MESSAGE_ID = 32
int32 iTOW # GPS time of week of the navigation epoch [ms]
int16 week # GPS week number of the navigation epoch [weeks]
uint8 numVis # Number of visible satellites
uint8 numSV # Number of per-SV data blocks following
RxmSVSI_SV[] sv

View File

@@ -0,0 +1,22 @@
# see message RxmSVSI
#
uint8 svid # Satellite ID
uint8 svFlag # Information Flags
uint8 FLAG_URA_MASK = 15 # Figure of Merit (URA) range 0..15
uint8 FLAG_HEALTHY = 16 # SV healthy flag
uint8 FLAG_EPH_VAL = 32 # Ephemeris valid
uint8 FLAG_ALM_VAL = 64 # Almanac valid
uint8 FLAG_NOT_AVAIL = 128 # SV not available
int16 azim # Azimuth
int8 elev # Elevation
uint8 age # Age of Almanac and Ephemeris
uint8 AGE_ALM_MASK = 15 # Age of ALM in days offset by 4
# i.e. the reference time may be in the future:
# ageOfAlm = (age & 0x0f) - 4
uint8 AGE_EPH_MASK = 240 # Age of EPH in hours offset by 4.
# i.e. the reference time may be in the future:
# ageOfEph = ((age & 0xf0) >> 4) - 4

View File

@@ -0,0 +1,25 @@
# UPD-SOS (0x09 0x14)
#
# Firmware Supported on:
# u-blox 8 / u-blox M8 from protocol version 15 up to version 23.01
#
uint8 CLASS_ID = 9
uint8 MESSAGE_ID = 20
uint8 cmd # Command
# The host can send this message in order to save part of the BBR memory in a
# file in flash file system. The feature is designed in order to emulate the
# presence of the backup battery even if it is not present; the host can issue
# the save on shutdown command before switching off the device supply. It is
# recommended to issue a GNSS stop command before, in order to keep the BBR
# memory content consistent.
uint8 CMD_FLASH_BACKUP_CREATE = 0 # Create Backup File in Flash
# The host can send this message in order to erase the backup file present in
# flash. It is recommended that the clear operation is issued after the host has
# received the notification that the memory has been restored after a reset.
# Alternatively the host can parse the startup string 'Restored data saved on
# shutdown' or poll the UBX-UPD-SOS message for getting the status.
uint8 CMD_FLASH_BACKUP_CLEAR = 1 # Clear Backup File in Flash
uint8[3] reserved1 # Reserved

View File

@@ -0,0 +1,38 @@
# UPD-SOS (0x09 0x14)
#
# Backup File Creation Acknowledge / System Restored from Backup
#
# Firmware Supported on:
# u-blox 8 / u-blox M8 from protocol version 15 up to version 23.01
#
uint8 CLASS_ID = 9
uint8 MESSAGE_ID = 20
uint8 cmd # Command
uint8 CMD_BACKUP_CREATE_ACK = 2 # Backup File Creation Acknowledge
# The message is sent from the device as
# confirmation of creation of a backup file
# in flash. The host can safely shut down the
# device after received this message.
uint8 CMD_SYSTEM_RESTORED = 3 # System Restored from Backup
# The message is sent from the device to
# notify the host the BBR has been restored
# from a backup file in flash. The host
# should clear the backup file after
# receiving this message. If the UBX-UPD-SOS
# message is polled, this message will be
# present.
uint8[3] reserved0 # Reserved
uint8 response # Response:
uint8 BACKUP_CREATE_NACK = 0 # Not acknowledged
uint8 BACKUP_CREATE_ACK = 1 # Acknowledged
uint8 SYSTEM_RESTORED_RESPONSE_UNKNOWN = 0 # Unknown
uint8 SYSTEM_RESTORED_RESPONSE_FAILED = 1 # Failed restoring from backup
# file
uint8 SYSTEM_RESTORED_RESPONSE_RESTORED = 2 # Restored from backup file
uint8 SYSTEM_RESTORED_RESPONSE_NOT_RESTORED = 3 # Not restored (no backup)
uint8[3] reserved1 # Reserved

View File

@@ -0,0 +1,32 @@
<package>
<name>ublox_msgs</name>
<version>1.1.2</version>
<description>
ublox_msgs contains raw messages for u-blox GNSS devices.
</description>
<author>Johannes Meyer</author>
<maintainer email="vmlane@alum.mit.edu">Veronica Lane</maintainer>
<license>BSD</license>
<url>http://ros.org/wiki/ublox</url>
<buildtool_depend>catkin</buildtool_depend>
<buildtool_depend>message_generation</buildtool_depend>
<run_depend>message_runtime</run_depend>
<build_depend>ublox_serialization</build_depend>
<run_depend>ublox_serialization</run_depend>
<build_depend>std_msgs</build_depend>
<run_depend>std_msgs</run_depend>
<build_depend>sensor_msgs</build_depend>
<run_depend>sensor_msgs</run_depend>
<export>
<rosdoc external="http://www.u-blox.com/en/product-resources"/>
</export>
</package>

View File

@@ -0,0 +1,191 @@
//==============================================================================
// Copyright (c) 2012, Johannes Meyer, TU Darmstadt
// All rights reserved.
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
// * Neither the name of the Flight Systems and Automatic Control group,
// TU Darmstadt, nor the names of its contributors may be used to
// endorse or promote products derived from this software without
// specific prior written permission.
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
// DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
// (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
// ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
// SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//==============================================================================
#include <ublox/serialization/ublox_msgs.h>
template <typename T>
std::vector<std::pair<uint8_t,uint8_t> > ublox::Message<T>::keys_;
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::NAV, ublox_msgs::Message::NAV::ATT,
ublox_msgs, NavATT);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::NAV, ublox_msgs::Message::NAV::CLOCK,
ublox_msgs, NavCLOCK);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::NAV, ublox_msgs::Message::NAV::DGPS,
ublox_msgs, NavDGPS);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::NAV, ublox_msgs::Message::NAV::DOP,
ublox_msgs, NavDOP);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::NAV, ublox_msgs::Message::NAV::POSECEF,
ublox_msgs, NavPOSECEF);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::NAV, ublox_msgs::Message::NAV::POSLLH,
ublox_msgs, NavPOSLLH);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::NAV,
ublox_msgs::Message::NAV::RELPOSNED,
ublox_msgs,
NavRELPOSNED);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::NAV, ublox_msgs::Message::NAV::SBAS,
ublox_msgs, NavSBAS);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::NAV, ublox_msgs::Message::NAV::SOL,
ublox_msgs, NavSOL);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::NAV, ublox_msgs::Message::NAV::PVT,
ublox_msgs, NavPVT);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::NAV, ublox_msgs::Message::NAV::PVT,
ublox_msgs, NavPVT7);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::NAV, ublox_msgs::Message::NAV::SAT,
ublox_msgs, NavSAT);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::NAV, ublox_msgs::Message::NAV::STATUS,
ublox_msgs, NavSTATUS);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::NAV, ublox_msgs::Message::NAV::SVIN,
ublox_msgs, NavSVIN);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::NAV, ublox_msgs::Message::NAV::SVINFO,
ublox_msgs, NavSVINFO);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::NAV, ublox_msgs::Message::NAV::TIMEGPS,
ublox_msgs, NavTIMEGPS);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::NAV, ublox_msgs::Message::NAV::TIMEUTC,
ublox_msgs, NavTIMEUTC);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::NAV, ublox_msgs::Message::NAV::VELECEF,
ublox_msgs, NavVELECEF);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::NAV, ublox_msgs::Message::NAV::VELNED,
ublox_msgs, NavVELNED);
// ACK messages are declared differently because they both have the same
// protocol, so only 1 ROS message is used
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::ACK, ublox_msgs::Message::ACK::NACK,
ublox_msgs, Ack);
DECLARE_UBLOX_MESSAGE_ID(ublox_msgs::Class::ACK, ublox_msgs::Message::ACK::ACK,
ublox_msgs, Ack, ACK);
// INF messages are declared differently because they all have the same
// protocol, so only 1 ROS message is used. DECLARE_UBLOX_MESSAGE can only
// be called once, and DECLARE_UBLOX_MESSAGE_ID is called for the following
// messages
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::INF, ublox_msgs::Message::INF::ERROR,
ublox_msgs, Inf);
DECLARE_UBLOX_MESSAGE_ID(ublox_msgs::Class::INF,
ublox_msgs::Message::INF::WARNING,
ublox_msgs, Inf, WARNING);
DECLARE_UBLOX_MESSAGE_ID(ublox_msgs::Class::INF,
ublox_msgs::Message::INF::NOTICE,
ublox_msgs, Inf, NOTICE);
DECLARE_UBLOX_MESSAGE_ID(ublox_msgs::Class::INF,
ublox_msgs::Message::INF::TEST,
ublox_msgs, Inf, TEST);
DECLARE_UBLOX_MESSAGE_ID(ublox_msgs::Class::INF,
ublox_msgs::Message::INF::DEBUG,
ublox_msgs, Inf, DEBUG);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::RXM, ublox_msgs::Message::RXM::ALM,
ublox_msgs, RxmALM);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::RXM, ublox_msgs::Message::RXM::EPH,
ublox_msgs, RxmEPH);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::RXM, ublox_msgs::Message::RXM::RAW,
ublox_msgs, RxmRAW);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::RXM, ublox_msgs::Message::RXM::RAWX,
ublox_msgs, RxmRAWX);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::RXM, ublox_msgs::Message::RXM::RTCM,
ublox_msgs, RxmRTCM);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::RXM, ublox_msgs::Message::RXM::SFRB,
ublox_msgs, RxmSFRB);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::RXM, ublox_msgs::Message::RXM::SFRBX,
ublox_msgs, RxmSFRBX);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::RXM, ublox_msgs::Message::RXM::SVSI,
ublox_msgs, RxmSVSI);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::CFG, ublox_msgs::Message::CFG::ANT,
ublox_msgs, CfgANT);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::CFG, ublox_msgs::Message::CFG::CFG,
ublox_msgs, CfgCFG);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::CFG, ublox_msgs::Message::CFG::DAT,
ublox_msgs, CfgDAT);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::CFG, ublox_msgs::Message::CFG::DGNSS,
ublox_msgs, CfgDGNSS);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::CFG, ublox_msgs::Message::CFG::GNSS,
ublox_msgs, CfgGNSS);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::CFG, ublox_msgs::Message::CFG::HNR,
ublox_msgs, CfgHNR);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::CFG, ublox_msgs::Message::CFG::INF,
ublox_msgs, CfgINF);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::CFG, ublox_msgs::Message::CFG::MSG,
ublox_msgs, CfgMSG);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::CFG, ublox_msgs::Message::CFG::NAV5,
ublox_msgs, CfgNAV5);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::CFG, ublox_msgs::Message::CFG::NAVX5,
ublox_msgs, CfgNAVX5);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::CFG, ublox_msgs::Message::CFG::NMEA,
ublox_msgs, CfgNMEA);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::CFG, ublox_msgs::Message::CFG::NMEA,
ublox_msgs, CfgNMEA6);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::CFG, ublox_msgs::Message::CFG::NMEA,
ublox_msgs, CfgNMEA7);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::CFG, ublox_msgs::Message::CFG::PRT,
ublox_msgs, CfgPRT);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::CFG, ublox_msgs::Message::CFG::RATE,
ublox_msgs, CfgRATE);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::CFG, ublox_msgs::Message::CFG::RST,
ublox_msgs, CfgRST);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::CFG, ublox_msgs::Message::CFG::TMODE3,
ublox_msgs, CfgTMODE3);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::CFG, ublox_msgs::Message::CFG::USB,
ublox_msgs, CfgUSB);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::UPD, ublox_msgs::Message::UPD::SOS,
ublox_msgs, UpdSOS);
// SOS and SOS_Ack have the same message ID, but different lengths
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::UPD, ublox_msgs::Message::UPD::SOS,
ublox_msgs, UpdSOS_Ack);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::MON, ublox_msgs::Message::MON::GNSS,
ublox_msgs, MonGNSS);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::MON, ublox_msgs::Message::MON::HW,
ublox_msgs, MonHW);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::MON, ublox_msgs::Message::MON::HW,
ublox_msgs, MonHW6);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::MON, ublox_msgs::Message::MON::VER,
ublox_msgs, MonVER);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::AID, ublox_msgs::Message::AID::ALM,
ublox_msgs, AidALM);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::AID, ublox_msgs::Message::AID::EPH,
ublox_msgs, AidEPH);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::AID, ublox_msgs::Message::AID::HUI,
ublox_msgs, AidHUI);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::ESF, ublox_msgs::Message::ESF::INS,
ublox_msgs, EsfINS);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::ESF, ublox_msgs::Message::ESF::MEAS,
ublox_msgs, EsfMEAS);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::ESF, ublox_msgs::Message::ESF::RAW,
ublox_msgs, EsfRAW);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::ESF, ublox_msgs::Message::ESF::STATUS,
ublox_msgs, EsfSTATUS);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::MGA, ublox_msgs::Message::MGA::GAL,
ublox_msgs, MgaGAL);
DECLARE_UBLOX_MESSAGE(ublox_msgs::Class::HNR, ublox_msgs::Message::HNR::PVT,
ublox_msgs, HnrPVT);