ROSaic = ROS + mosaic
Overview
This repository hosts drivers for ROS 1 (Melodic and Noetic) and ROS 2 (Foxy, Galactic, Humble, Iron, Rolling, and beyond) - written in C++ - that work with mosaic and AsteRx - two of Septentrio's cutting-edge GNSS and GNSS/INS receiver families - and beyond. Both ROS 1 and ROS 2 are supported within one repository.
Main Features:
- Supports Septentrio's single antenna GNSS, dual antenna GNSS and INS receivers
- Supports serial, TCP/IP and USB connections, the latter being compatible with both serial (RNDIS) and TCP/IP protocols
- Supports several ASCII (including key NMEA ones) messages and SBF (Septentrio Binary Format) blocks
- Reports status of AIM+ (Advanced Interference Mitigation including OSNMA) anti-jamming and anti-spoofing.
- Can publish
nav_msgs/Odometry
message for INS receivers
- Can blend SBF blocks
PVTGeodetic
, PosCovGeodetic
, ChannelStatus
, MeasEpoch
, AttEuler
, AttCovEuler
, VelCovGeodetic
and DOP
in order to publish gps_common/GPSFix
and sensor_msgs/NavSatFix
messages
- Supports optional axis convention conversion since Septentrio follows the NED convention, whereas ROS is ENU.
- Easy configuration of multiple RTK corrections simultaneously (via NTRIP, TCP/IP stream, or serial)
- Can play back PCAP capture logs for testing purposes
- Tested with the mosaic-X5, mosaic-H, AsteRx-m3 Pro+, AsteRx-SB Pro+ and the AsteRx-SBi3 Pro receiver
- Easy to add support for more log types
Please let the maintainers know of your success or failure in using the driver with other devices so we can update this page appropriately.
Usage
Important notes
Notes Before Usage
+ The driver assumes that our anonymous access to the Rx grants us full control rights. This should be the case by default, and can otherwise be changed with the `setDefaultAccessLevel` command. If user control is in place user credentials can be given by parameters `login.user` and `login.password`.
+ Note for serial connection: Make sure the user is part of the `dialout` group to have full access to the serial ports. If not, add it for example with `sudo adduser [username] dialout`.
+ Note for setting hw_flow_control: This is a string parameter, setting it to off without quotes leads to the fact that it is not read in correctly.
+ Note for setting ant_(aux1)_serial_nr: This is a string parameter, numeric only serial numbers should be put in quotes. If this is not done a warning will be issued and the driver tries to parse it as integer.
+ Note for usage of NTRIP via USB with virtual ethernet (RNDIS): RNDIS provides a virtual network connection only between the receiver and the PC. First outgoing network access via USB has to be activated, which is explained [here](https://www.youtube.com/watch?v=bUt8cL9Ue1Y). Next setup internet sharing under Linux by setting the connection of the virtual network interface (the name should be something like enx1a3202991545) to "Shared to other computers".
+ Once the build or binary installation is finished, adapt the `config/rover.yaml` file according to your needs or assemble a new one, examples for GNSS specific parameters `config/gnss.yaml` and INS `config/ins.yaml` are also available. Specify the communication parameters, the ROS messages to be published, the frequency at which the latter should happen etc.
ROS 1: Launch the `launch/rover.launch` to use `rover.yaml` or add `param_file_name:=xxx` to use a custom config.
ROS 2: Launch as composition with `ros2 launch septentrio_gnss_driver rover.launch.py` to use `rover.yaml` or add `file_name:=xxx.yaml` to use a custom config. Alternatively launch as node with `ros2 launch septentrio_gnss_driver rover_node.launch.py` to use `rover_node.yaml` or add `file_name:=xxx.yaml` to use a custom config. Specify the communication parameters, the ROS messages to be published, the frequency at which the latter should happen etc.
+ Besides the aforementioned config file `rover.yaml` containing all parameters, specialized launch files for GNSS `config/gnss.yaml` and INS `config/ins.yaml` respectively contain only the relevant parameters in each case.
- NOTE: Unless `configure_rx` is set to `false`, this driver will overwrite the previous values of the parameters, even if the value is left to zero in the "yaml" file.
+ The driver was developed and tested with firmware versions >= 4.10.0 for GNSS and >= 1.3.2 for INS. Receivers with older firmware versions are supported but some features may not be available. Known limitations are:
* GNSS with firmware < 4.10.0 does not support IP over USB.
* GNSS with firmware < 4.12.1 does not support OSNMA.
* GNSS with firmware < 4.14 does not support PTP server clock.
* INS with firmware <= 1.2.0 does not support velocity aiding.
* INS with firmware <= 1.2.0 does not support setting of initial heading.
* INS with firmware < 1.3.2 does not support NTP.
* INS with firmware < 1.4 does not support OSNMA.
* INS with firmware < 1.4.1 does not support improved VSM handling allowing for unknown variances.
* INS does not support PTP server clock as of now.
+ Known issues:
* UDP over USB: Blocks are sent twice on GNSS with firmware <= 4.12.1 and INS with firmware <= 1.4. For GNSS it is fixed in version 4.14 (released on June 15th 2023), for INS is fixed in 1.4.1 (released November 2023).
+ If `use_ros_axis_orientation` to `true` axis orientations are converted by the driver between NED (Septentrio: yaw = 0 is north, positive clockwise) and ENU (ROS: yaw = 0 is east, positive counterclockwise). There is no conversion when setting this parameter to `false` and the angles will be consistent with the web GUI in this case.
:
```
# Example configuration Settings for the Rover Rx
device: tcp://192.168.3.1:28784
serial:
baudrate: 921600
hw_flow_control: "off"
stream_device:
tcp:
ip_server: ""
port: 0
udp:
ip_server: ""
port: 0
unicast_ip: ""
configure_rx: true
custom_commands_file: ""
login:
user: ""
password: ""
osnma:
mode: "off"
ntp_server: ""
keep_open: true
frame_id: gnss
imu_frame_id: imu
poi_frame_id: base_link
vsm_frame_id: vsm
aux1_frame_id: aux1
vehicle_frame_id: base_link
insert_local_frame: false
local_frame_id: odom
get_spatial_config_from_tf: true
lock_utm_zone: true
use_ros_axis_orientation: true
receiver_type: gnss
datum: Default
poi_to_arp:
delta_e: 0.0
delta_n: 0.0
delta_u: 0.0
att_offset:
heading: 0.0
pitch: 0.0
ant_type: Unknown
ant_aux1_type: Unknown
ant_serial_nr: Unknown
ant_aux1_serial_nr: Unknown
leap_seconds: 18
polling_period:
pvt: 500
rest: 500
use_gnss_time: false
ntp_server: false
ptp_server_clock: false
latency_compensation: false
rtk_settings:
ntrip_1:
id: "NTR1"
caster: "1.2.3.4"
caster_port: 2101
username: "Asterix"
password: "password"
mountpoint: "mtpt1"
version: "v2"
tls: true
fingerprint: "AA:BB:56:78:90:12: ... 78:90:12:34"
rtk_standard: "RTCMv3"
send_gga: "auto"
keep_open: true
ntrip_2:
id: "NTR3"
caster: "5.6.7.8"
caster_port: 2101
username: "Obelix"
password: "password"
mountpoint: "mtpt2"
version: "v2"
tls: false
fingerprint: ""
rtk_standard: "RTCMv2"
send_gga: "auto"
keep_open: true
ip_server_1:
id: "IPS3"
port: 28785
rtk_standard: "RTCMv2"
send_gga: "auto"
keep_open: true
ip_server_2:
id: "IPS5"
port: 28786
rtk_standard: "CMRv2"
send_gga: "auto"
keep_open: true
serial_1:
port: "COM1"
baud_rate: 230400
rtk_standard: "auto"
send_gga: "sec1"
keep_open: true
serial_2:
port: "COM2"
baud_rate: 230400
rtk_standard: "auto"
send_gga: "off"
keep_open: true
publish:
# For both GNSS and INS Rxs
auto_publish: false
publish_only_valid: false
navsatfix: false
gpsfix: true
gpgga: false
gprmc: false
gpst: false
measepoch: false
pvtcartesian: false
pvtgeodetic: true
basevectorcart: false
basevectorgeod: false
poscovcartesian: false
poscovgeodetic: true
velcovcartesian: false
velcovgeodetic: false
atteuler: true
attcoveuler: true
pose: false
twist: false
diagnostics: false
aimplusstatus: true
galauthstatus: false
# For GNSS Rx only
gpgsa: false
gpgsv: false
# For INS Rx only
insnavcart: false
insnavgeod: false
extsensormeas: false
imusetup: false
velsensorsetup: false
exteventinsnavcart: false
exteventinsnavgeod: false
imu: false
localization: false
tf: false
localization_ecef: false
tf_ecef: false
# INS-Specific Parameters
ins_spatial_config:
imu_orientation:
theta_x: 0.0
theta_y: 0.0
theta_z: 0.0
poi_lever_arm:
delta_x: 0.0
delta_y: 0.0
delta_z: 0.0
ant_lever_arm:
x: 0.0
y: 0.0
z: 0.0
vsm_lever_arm:
vsm_x: 0.0
vsm_y: 0.0
vsm_z: 0.0
ins_initial_heading: auto
ins_std_dev_mask:
att_std_dev: 5.0
pos_std_dev: 10.0
ins_use_poi: true
ins_vsm:
source: "twist"
config: [true, false, false]
variances_by_parameter: true
variances: [0.1, 0.0, 0.0]
ip_server:
id: "IPS2"
port: 28787
keep_open: true
serial:
port: "COM3"
baud_rate: 115200
keep_open: true
# Logger
activate_debug_log: false
```
In order to launch ROSaic, the launch command for ROS 1 reads `roslaunch septentrio_gnss_driver rover.launch param_file_name:=rover` and for ROS 2 reads `ros2 launch septentrio_gnss_driver rover.py file_name:=rover.yaml`. If multiple port are utilized for RTK corrections and/or VSM, which shall be closed after driver shutdown (`keep_open: false`), make sure to give the driver enough time to gracefully shutdown as closing the ports takes a few seconds. For ROS 2, this can be accomplished in the launch files by increasing the timeout of SIGTERM (e.g. `sigterm_timeout = '10',`), see example launch files`rover.launch.py`and `rover_node.launch.py` respectively.
Dependencies
ROS
This driver functions on ROS 1 [Melodic](https://wiki.ros.org/melodic/Installation/Ubuntu) and [Noetic](https://wiki.ros.org/noetic/Installation/Ubuntu) or ROS 2 [Foxy](https://docs.ros.org/en/foxy/Installation.html), [Galactic](https://docs.ros.org/en/galactic/Installation.html), [Humble](https://docs.ros.org/en/humble/Installation.html)
[Iron](https://docs.ros.org/en/iron/Installation.html), [Jazzy](https://docs.ros.org/en/jazzy/Installation.html), and [Rolling](https://docs.ros.org/en/rolling/Installation.html) (Ubuntu 18.04, 20.04, 22.04, or 24.04 respectively). It is thus necessary to install the ROS version that has been designed for your Linux distro.
Installation via apt
Binary Install
The binary release is available for ROS 1 (Melodic and Noetic) and ROS 2 (Foxy, Galactic, Humble, Iron, Jazzy, and Rolling). Since Melodic, Foxy, and Galactic are EOL, only Noetic, Humble, Iron, Jazzy, and Rolling will get updated versions. To install the binary package, simply run `sudo apt-get install ros-$ROS_DISTRO-septentrio-gnss-driver`.
Build from source
Build
+ Building ROSaic only works from C++17 onwards due to the usage of std::any() etc.
#### Dependencies for development
Additional ROS packages have to be installed for the NMEA and GPSFix messages.
ROS 1: `sudo apt install ros-$ROS_DISTRO-nmea-msgs ros-$ROS_DISTRO-gps-common`.
ROS 2: `sudo apt install ros-$ROS_DISTRO-nmea-msgs ros-$ROS_DISTRO-gps-msgs`.
The serial and TCP/IP communication interface of the ROS driver is established by means of the [Boost C++ library](https://www.boost.org/). In the unlikely event that the below installation instructions fail to install Boost on the fly, please install the Boost libraries via
`sudo apt install libboost-all-dev`.
Conversions from LLA to UTM are incorporated through [GeographicLib](https://geographiclib.sourceforge.io/). Install the necessary headers via
`sudo apt install libgeographic-dev`
or
`sudo apt install libgeographiclib-dev`
since Ubunutu 24.04. respectively.
Compatiblity with PCAP captures are incorporated through [pcap libraries](https://github.com/the-tcpdump-group/libpcap). Install the necessary headers via
`sudo apt install libpcap-dev`.
#### ROS 1
For ROS 1, the package can be built from source using [`catkin_tools`](https://catkin-tools.readthedocs.io/en/latest/installing.html), where the latter can be installed using the command
`sudo apt-get install python-catkin-tools` for Melodic or `sudo apt-get install python3-catkin-tools` for Noetic. The typical `catkin_tools` [workflow](https://catkin-tools.readthedocs.io/en/latest/quick_start.html) should suffice:
```
source /opt/ros/${ROS_DISTRO}/setup.bash # In case you do not use the default shell of Ubuntu, you need to source another script, e.g. setup.sh.
mkdir -p ~/septentrio/src # Note: Change accordingly depending on where you want your package to be installed.
cd ~/septentrio
catkin init # Initialize with a hidden marker file
catkin config --cmake-args -DCMAKE_BUILD_TYPE=RelWithDebInfo # CMake build types pass compiler-specific flags to your compiler. This type amounts to a release with debug info, while keeping debugging symbols and doing optimization. I.e. for GCC the flags would be -O2, -g and -DNDEBUG.
cd src
git clone https://github.com/septentrio-gnss/septentrio_gnss_driver
rosdep install . --from-paths -i # Might raise "rosaic: Unsupported OS [mint]" warning, if your OS is Linux Mint, since rosdep does not know Mint (and possible other OSes). In that case, add the "--os=ubuntu:saucy" option to "fool" rosdep into believing it faces some Ubuntu version. The syntax is "--os=OS_NAME:OS_VERSION".
catkin build # If catkin cannot find empty, tell catkin to use Python 3 by adding "-DPYTHON_EXECUTABLE=/usr/bin/python3".
echo "source ~/septentrio/devel/setup.bash" >> ~/.bashrc # It is convenient if the ROS environment variable is automatically added to your bash session every time a new shell is launched. Again, this works for bash shells only. Also note that if you have more than one ROS distribution installed, ~/.bashrc must only source the setup.bash for the version you are currently using.
source ~/.bashrc
```
#### ROS 2
For ROS 2, The package has to be built from source using [`colcon`](https://docs.ros.org/en/humble/Tutorials/Beginner-Client-Libraries/Colcon-Tutorial.html):
```
source /opt/ros/${ROS_DISTRO}/setup.bash # In case you do not use the default shell of Ubuntu, you need to source another script, e.g. setup.sh.
mkdir -p ~/septentrio/src # Note: Change accordingly depending on where you want your package to be installed.
cd ~/septentrio/src
git clone https://github.com/septentrio-gnss/septentrio_gnss_driver
git checkout ros2 # Install mentioned dependencies (`sudo apt install ros-$ROS_DISTRO-nmea_msgs ros-$ROS_DISTRO-gps-msgs libboost-all-dev libpcap-dev libgeographic-dev`)
colcon build --packages-up-to septentrio_gnss_driver # Be sure to call colcon build in the root folder of your workspace. Launch files are installed, so changing them on the fly in the source folder only works with installing by symlinks: add `--symlink-install`
echo "source ~/septentrio/devel/setup.bash" >> ~/.bashrc # It is convenient if the ROS environment variable is automatically added to your bash session every time a new shell is launched. Again, this works for bash shells only. Also note that if you have more than one ROS distribution installed, ~/.bashrc must only source the setup.bash for the version you are currently using.
source ~/.bashrc
```
Run tests
```
colcon test --packages-select septentrio_gnss_driver --event-handlers console_direct+
```
Inertial Navigation System (INS): Basics
-
An Inertial Navigation System (INS) is a device which takes the rotation and acceleration solutions as obtained from its Inertial Measurement Unit (IMU) and combines those with position and velocity information from the GNSS module. Compared to a GNSS system with 7D or 8D (dual-antenna systems) phase space solutions, the combined, Kalman-filtered 9D phase space solution (3 for position, 3 for velocity, 3 for orientation) of an INS is more accurate, more precise and more stable against GNSS outages.
-
The IMU is typically made up of a 3-axis accelerometer, a 3-axis gyroscope and sometimes a 3-axis magnetometer and measures the system's angular rate and acceleration.
Measure and Compensate for IMU-Antenna Lever Arm
+ The IMU-antenna lever-arm is the relative position between the IMU reference point and the GNSS Antenna Reference Point (ARP), measured in the vehicle frame.
+ In case of AsteRx SBi3, the IMU reference point is clearly marked on the top panel of the receiver. It is important to compensate for the effect of the lever arm, otherwise the receiver may not be able to calculate an accurate INS position.
+ The IMU/antenna position can be changed by specifying the lever arm's `x`,`y`and `z` parameters in the `config.yaml` file under the `ins_spatial_config.ant_lever_arm` parameter.
![Screenshot from 2021-08-03 09-23-19 (1)](https://user-images.githubusercontent.com/62261460/127984869-f6892a30-e30d-4d41-bee3-ee1e4bfceab8.jpg)
Compensate for IMU Orientation
+ It is important to take into consideration the mounting direction of the IMU in the body frame of the vehicle. For e.g. when the receiver is installed horizontally with the front panel facing the direction of travel, we must compensate for the IMU’s orientation to make sure the IMU reference frame is aligned with the vehicle reference frame. The IMU position and orientation is printed on the top panel, cf. image below.
+ The IMU's orientation can be changed by specifying the orientation angles `theta_x`,`theta_y`and `theta_z` in the `config.yaml` file under `ins_spatial_config.imu_orientation`
+ The below image illustrates the orientation of the IMU reference frame with the associated IMU orientation for the depicted installation. Note that for `use_ros_axis_orientation: true` sensor_default is the top left position.
![Capture (1)](https://user-images.githubusercontent.com/62261460/135855781-96459583-5268-4cf0-8995-f00cd0bd91e9.jpg)
-
These Steps should be followed to configure the receiver in INS integration mode:
- Specify
receiver_type: INS
- Specify the orientation of the IMU sensor with respect to your vehicle, using the
ins_spatial_config.imu_orientation
parameter.
- Specify the IMU-antenna lever arm in the vehicle reference frame. This is the vector starting from the IMU reference point to the ARP of the main GNSS antenna. This can be done by means of the
ins_spatial_config.ant_lever_arm
parameter.
- Specify
ins_spatial_config.vsm_lever_arm
if measurements of a velocity sensor is available.
- Alternatively the lever arms may be specified via tf. Set
get_spatial_config_from_tf
to true
in this case.
- If the point of interest is neither the IMU nor the ARP of the main GNSS antenna, the vector between the IMU and the point of interest can be provided with the
ins_solution/poi_lever_arm
parameter.
-
For further more information about Septentrio receivers, visit Septentrio support resources or check out the user manual and reference guide of the AsteRx SBi3 receiver.
ROSaic Parameters
The following is a list of ROSaic parameters found in the config/rover.yaml
file. Note, that in the following nested parameters are depicted in ROS 2 style, i.e., using a .
as delimiter, whereas in ROS 1 the delimiter is a /
.
ROS Topic Publications
A selection of NMEA sentences, the majority being standardized sentences, and proprietary SBF blocks is translated into ROS messages, partly generic and partly custom, and can be published at the discretion of the user into the following ROS topics. All published ROS messages, even custom ones, start with a ROS generic header std_msgs/Header.msg
, which includes the receiver time stamp as well as the frame ID, the latter being specified in the ROS parameter frame_id
.
Available ROS Topics
+ `/gpgga`: publishes [`nmea_msgs/Gpgga.msg`](https://docs.ros.org/api/nmea_msgs/html/msg/Gpgga.html) - converted from the NMEA sentence GGA.
+ `/gprmc`: publishes [`nmea_msgs/Gprmc.msg`](https://docs.ros.org/api/nmea_msgs/html/msg/Gprmc.html) - converted from the NMEA sentence RMC.
+ `/gpgsa`: publishes [`nmea_msgs/Gpgsa.msg`](https://docs.ros.org/api/nmea_msgs/html/msg/Gpgsa.html) - converted from the NMEA sentence GSA.
+ `/gpgsv`: publishes [`nmea_msgs/Gpgsv.msg`](https://docs.ros.org/api/nmea_msgs/html/msg/Gpgsv.html) - converted from the NMEA sentence GSV.
+ `/measepoch`: publishes custom ROS message `septentrio_gnss_driver/MeasEpoch.msg`, corresponding to the SBF block `MeasEpoch`.
+ `/galauthstatus`: publishes custom ROS message `septentrio_gnss_driver/GALAuthStatus.msg`, corresponding to the SBF block `GALAuthStatus`.
+ `/rfstatus`: publishes custom ROS message `septentrio_gnss_driver/RFStatus.msg`, compiled from the SBF block `RFStatus`.
+ `/aimplusstatus`: publishes custom ROS message `septentrio_gnss_driver/AIMPlusStatus.msg`, reporting status of AIM+. Converted from SBF blocks `RFStatus` and optionally `GALAuthStatus`. For the latter OSNMA has to be activated.
+ `/pvtcartesian`: publishes custom ROS message `septentrio_gnss_driver/PVTCartesian.msg`, corresponding to the SBF block `PVTCartesian` (GNSS case) or `INSNavGeod` (INS case).
+ `/pvtgeodetic`: publishes custom ROS message `septentrio_gnss_driver/PVTGeodetic.msg`, corresponding to the SBF block `PVTGeodetic` (GNSS case) or `INSNavGeod` (INS case).
+ `/basevectorcart`: publishes custom ROS message `septentrio_gnss_driver/BaseVectorCart.msg`, corresponding to the SBF block `BaseVectorCart`.
+ `/basevectorgeod`: publishes custom ROS message `septentrio_gnss_driver/BaseVectorGeod.msg`, corresponding to the SBF block `BaseVectorGeod`.
+ `/poscovcartesian`: publishes custom ROS message `septentrio_gnss_driver/PosCovCartesian.msg`, corresponding to SBF block `PosCovCartesian` (GNSS case) or `INSNavGeod` (INS case).
+ `/poscovgeodetic`: publishes custom ROS message `septentrio_gnss_driver/PosCovGeodetic.msg`, corresponding to SBF block `PosCovGeodetic` (GNSS case) or `INSNavGeod` (INS case).
+ `/velcovcartesian`: publishes custom ROS message `septentrio_gnss_driver/VelCovCartesian.msg`, corresponding to SBF block `VelCovCartesian` (GNSS case).
+ `/velcovgeodetic`: publishes custom ROS message `septentrio_gnss_driver/VelCovGeodetic.msg`, corresponding to SBF block `VelCovGeodetic` (GNSS case).
+ `/atteuler`: publishes custom ROS message `septentrio_gnss_driver/AttEuler.msg`, corresponding to SBF block `AttEuler`.
+ `/attcoveuler`: publishes custom ROS message `septentrio_gnss_driver/AttCovEuler.msg`, corresponding to the SBF block `AttCovEuler`.
+ `/gpst` (for GPS Time): publishes generic ROS message [`sensor_msgs/TimeReference.msg`](https://docs.ros2.org/foxy/api/sensor_msgs/msg/TimeReference.html), converted from the `PVTGeodetic` (GNSS case) or `INSNavGeod` (INS case) block's GPS time information, stored in its block header.
+ `/navsatfix`: publishes generic ROS message [`sensor_msgs/NavSatFix.msg`](https://docs.ros2.org/foxy/api/sensor_msgs/msg/NavSatFix.html), converted from the SBF blocks `PVTGeodetic`,`PosCovGeodetic` (GNSS case) or `INSNavGeod` (INS case)
+ The ROS message [`sensor_msgs/NavSatFix.msg`](https://docs.ros2.org/foxy/api/sensor_msgs/msg/NavSatFix.html) can be fed directly into the [`navsat_transform_node`](https://docs.ros.org/en/api/robot_localization/html/navsat_transform_node.html) of the ROS navigation stack.
+ `/gpsfix`: publishes generic ROS message [`gps_msgs/GPSFix.msg`](https://github.com/swri-robotics/gps_umd/blob/ros2-devel/gps_msgs/msg/GPSFix.msg), which is much more detailed than [`sensor_msgs/NavSatFix.msg`](https://docs.ros2.org/foxy/api/sensor_msgs/msg/NavSatFix.html), converted from the SBF blocks `PVTGeodetic`, `PosCovGeodetic`, `ChannelStatus`, `MeasEpoch`, `AttEuler`, `AttCovEuler`, `VelCovGeodetic`, `DOP` (GNSS case) or `INSNavGeod`, `ChannelStatus`, `MeasEpoch`, `DOP` (INS case). In order to publish heading information, the field *dip* is diverted from its intended meaning an populated with the heading angle and *err_dip* with its uncertainty.
+ INS case: **Beware**, in order to allow a high update rate, `ChannelStatus`, `MeasEpoch`, and `DOP` are not time aligned, i.e., they might contain outdated information.
+ `/pose`: publishes generic ROS message [`geometry_msgs/PoseWithCovarianceStamped.msg`](https://docs.ros2.org/foxy/api/geometry_msgs/msg/PoseWithCovarianceStamped.html), converted from the SBF blocks `PVTGeodetic`, `PosCovGeodetic`, `AttEuler`, `AttCovEuler` (GNSS case) or `INSNavGeod` (INS case).
+ Note that GNSS provides absolute positioning, while robots are often localized within a local level cartesian frame. The pose field of this ROS message contains position with respect to the absolute ENU frame (longitude, latitude, height), i.e. not a cartesian frame, while the orientation is with respect to a vehicle-fixed (e.g. for mosaic-x5 in moving base mode via the command `setAttitudeOffset`, ...) !local! NED frame or ENU frame if `use_ros_axis_directions` is set `true`. Thus the orientation is !not! given with respect to the same frame as the position is given in. The cross-covariances are hence set to 0.
+ `/twist`: publishes generic ROS message [`geometry_msgs/TwistWithCovarianceStamped.msg`](https://docs.ros2.org/foxy/api/geometry_msgs/msg/TwistWithCovarianceStamped.html), converted from the SBF blocks `PVTGeodetic` and `VelCovGeodetic`.
+ `/twist_ins`: publishes generic ROS message [`geometry_msgs/TwistWithCovarianceStamped.msg`](https://docs.ros2.org/foxy/api/geometry_msgs/msg/TwistWithCovarianceStamped.html), converted from SBF block `INSNavGeod`.
+ `/insnavcart`: publishes custom ROS message `septentrio_gnss_driver/INSNavCart.msg`, corresponding to SBF block `INSNavCart`
+ `/insnavgeod`: publishes custom ROS message `septentrio_gnss_driver/INSNavGeod.msg`, corresponding to SBF block `INSNavGeod`
+ `/extsensormeas`: publishes custom ROS message `septentrio_gnss_driver/ExtSensorMeas.msg`, corresponding to SBF block `ExtSensorMeas`.
+ `/imusetup`: publishes custom ROS message `septentrio_gnss_driver/IMUSetup.msg`, corresponding to SBF block `IMUSetup`.
+ `/velsensorsetup`: publishes custom ROS message `septentrio_gnss_driver/VelSensorSetup.msg` corresponding to SBF block `VelSensorSetup`.
+ `/exteventinsnavcart`: publishes custom ROS message `septentrio_gnss_driver/INSNavCart.msg`, corresponding to SBF block `ExtEventINSNavCart`.
+ `/exteventinsnavgeod`: publishes custom ROS message `septentrio_gnss_driver/INSNavGeod.msg`, corresponding to SBF block `ExtEventINSNavGeod`.
+ `/diagnostics`: accepts generic ROS message [`diagnostic_msgs/DiagnosticArray.msg`](https://docs.ros2.org/foxy/api/diagnostic_msgs/msg/DiagnosticArray.html), converted from the SBF blocks `QualityInd`, `ReceiverStatus` and `ReceiverSetup`
+ `/imu`: accepts generic ROS message [`sensor_msgs/Imu.msg`](https://docs.ros2.org/foxy/api/sensor_msgs/msg/Imu.html), converted from the SBF blocks `ExtSensorMeas` and `INSNavGeod`.
+ The ROS message [`sensor_msgs/Imu.msg`](https://docs.ros2.org/foxy/api/sensor_msgs/msg/Imu.html) can be fed directly into the [`robot_localization`](https://docs.ros.org/en/api/robot_localization/html/preparing_sensor_data.html) of the ROS navigation stack. Note that `use_ros_axis_orientation` should be set to `true` to adhere to the ENU convention.
+ `/localization`: accepts generic ROS message [`nav_msgs/Odometry.msg`](https://docs.ros2.org/foxy/api/nav_msgs/msg/Odometry.html), converted from the SBF block `INSNavGeod` and transformed to UTM.
+ The ROS message [`nav_msgs/Odometry.msg`](https://docs.ros2.org/foxy/api/nav_msgs/msg/Odometry.html) can be fed directly into the [`robot_localization`](https://docs.ros.org/en/api/robot_localization/html/preparing_sensor_data.html) of the ROS navigation stack. Note that `use_ros_axis_orientation` should be set to `true` to adhere to the ENU convention.
+ `/localization_ecef`: accepts generic ROS message [`nav_msgs/Odometry.msg`](https://docs.ros2.org/foxy/api/nav_msgs/msg/Odometry.html), converted from the SBF blocks `INSNavCart` and `INSNavGeod`.
+ The ROS message [`nav_msgs/Odometry.msg`](https://docs.ros2.org/foxy/api/nav_msgs/msg/Odometry.html) can be fed directly into the [`robot_localization`](https://docs.ros.org/en/api/robot_localization/html/preparing_sensor_data.html) of the ROS navigation stack. Note that `use_ros_axis_orientation` should be set to `true` to adhere to the ENU convention.
Suggestions for Improvements
Some Ideas
+ Equip ROSaic with an NTRIP client such that it can forward corrections to the receiver independently of `Data Link`.
Adding New SBF Blocks or NMEA Sentences
Steps to Follow
Is there an SBF or NMEA message that is not being addressed while being important to your application? If yes, follow these steps:
1. Find the log reference of interest in the publicly accessible, official documentation. Hence select the reference guide file, e.g. for mosaic-x5 in the [product support section for mosaic-X5](https://www.septentrio.com/en/support/mosaic/mosaic-x5), Chapter 4, of Septentrio's homepage.
2. SBF: Add a new `.msg` file to the `../msg` folder. And modify the `../CMakeLists.txt` file by adding a new entry to the `add_message_files` section.
3. Add msg header and typedef to `typedefs.hpp`.
4. Parsers:
- SBF: Add a parser to the `sbf_blocks.hpp` file.
- NMEA: Construct two new parsing files such as `gpgga.cpp` to the `../src/septentrio_gnss_driver/parsers/nmea_parsers` folder and one such as `gpgga.hpp` to the `../include/septentrio_gnss_driver/parsers/nmea_parsers` folder.
5. Processing the message/block:
- SBF: Extend the `SbfId` enumeration in the `message_handler.hpp` file with a new entry.
- SBF: Extend the SBF switch-case in `message_handler.cpp` file with a new case.
- NMEA: Extend the `nmeaMap_` in the `message_handler.hpp` file with a new pair.
- NMEA: Extend the NMEA switch-case in `message_handler.cpp` file with a new case.
6. Create a new `publish/..` ROSaic parameter in the `../config/rover.yaml` file and create a boolean variable `publish_xxx` in the struct in the `settings.h` file. Parse the parameter in the `rosaic_node.cpp` file.
7. Add SBF block or NMEA to data stream setup in `communication_core.cpp` (function `configureRx()`).