README
sbg_driver
ROS2 driver package for SBG Systems IMU, AHRS and INS. This driver package uses the sbgECom binary protocol to read data and configure SBG Systems devices.
Initial work has been done by ENSTA Bretagne.
Author: SBG Systems Maintainer: SBG Systems Contact: support@sbg-systems.com
Features
The driver supports all SBG systems sensors, IMUs, AHRS and INS, with a various degree of configurations available.
The driver supports the following features:
- Parse IMU/AHRS/INS/GNSS using the sbgECom protocol 
- Publish standard ROS2 messages and more detailed specific SBG Systems topics 
- Subscribe and forward RTCM data to support DGPS/RTK mode with centimeters-level accuracy 
- Calibrate 2D/3D magnetic field using the on-board ELLIPSE algorithms 
- Configure ELLIPSE products using yaml files (see note below) 
[!NOTE] While the ROS2 drivers can be used with all SBG Systems sensors, the drivers can only be used to configure the Ellipse family. For other INS such as EKINOX, APOGEE and QUANTA, please use the sbgInsRestApi For the PULSE-40, please use the sbgEcom encapsulation of the sbgInsRestApi: see our Getting started Guide
Installation
Installation from Packages
User can install the sbg_ros2_driver through the standard ROS2 installation system.
- Humble - sudo apt-get install ros-humble-sbg-driver
- Galactic - sudo apt-get install ros-galactic-sbg-driver
- Foxy - sudo apt-get install ros-foxy-sbg-driver
Building from sources
Dependencies
- sbgECom C Library (embeds v4.0.1987-stable - compatible with ELLIPSE firmware 2.5 and above) 
Building
- Clone the repository (use a Release version) 
- Build using the ROS2 colcon build system 
cd colcon_ws/src
git clone https://github.com/SBG-Systems/sbg_ros2_driver.git
cd sbg_ros2_driver
rosdep update
rosdep install --from-path .
cd ../..
colcon build
source install/setup.bash
Usage
To run the default ROS2 node with the default configuration file
ros2 launch sbg_driver sbg_device_launch.py
To run the magnetic calibration node
ros2 launch sbg_driver sbg_device_mag_calibration_launch.py
Config files
Default config files
Every configuration file is defined according to the same structure.
- sbg_device_uart_default.yaml This config file is the default one for UART connection with the device. It does not configure the device through the ROS2 node, so it has to be previously configured (manually or with the ROS2 node). It defines a few outputs for the device: - /sbg/imu_data,- /sbg/ekf_quatat 25Hz
- ROS2 standard outputs - /imu/data,- /imu/velocity,- /imu/tempat 25Hz
- /sbg/status,- /sbg/utc_timeand- /imu/utc_refat 1Hz.
 
- sbg_device_udp_default.yaml This config file is the default one for an UDP connection with the device. It does not configure the device through the ROS2 node, so it has to be previously configured (manually). It defines a few outputs for the device: - /sbg/imu_data,- /sbg/ekf_quatat 25Hz
- ROS2 standard outputs - /imu/data,- /imu/velocity,- /imu/tempat 25Hz
- /sbg/status,- /sbg/utc_timeand- /imu/utc_refat 1Hz.
 
Example config files
- ellipse_A_default.yaml Default config file for an Ellipse-A. 
- ellipse_E_default.yaml Default config file for an Ellipse-E with an external NMEA GNSS. 
- ellipse_N_default.yaml Default config file for an Ellipse-N using internal GNSS. 
- ellipse_D_default.yaml Default config file for an Ellipse-D using internal GNSS. 
Launch files
Default launch files
- sbg_device_launch.py Launch the sbg_device node to handle the received data, and load the - sbg_device_uart_default.yamlconfiguration.
- sbg_device_mag_calibration_launch.py Launch the sbg_device_mag node to calibrate the magnetometers, and load the - ellipse_E_default.yamlconfiguration.
Nodes
sbg_device node
The sbg_device node handles the communication with the connected device, publishes the SBG output to the ROS2 environment and subscribes to useful topics such as RTCM data streams.
Published Topics
SBG Systems specific topics
SBG Systems has defined proprietary ROS2 messages to report more detailed information from the AHRS/INS. These messages try to match as much as possible the sbgECom logs as they are output by the device.
[!NOTE] Please refer to the firmware manual to check the availability of the outputs per product.
- /sbg/statussbg_driver/SbgStatus- Provides information about the general status (Communication, Aiding, etc..). 
- /sbg/utc_timesbg_driver/SbgUtcTime- Provides UTC time reference. 
- /sbg/imu_datasbg_driver/SbgImuData- IMU status, and sensors values. 
- /sbg/ekf_eulersbg_driver/SbgEkfEuler- Computed orientation using Euler angles. 
- /sbg/ekf_quatsbg_driver/SbgEkfQuat- Computed orientation using Quaternion. 
- /sbg/ekf_navsbg_driver/SbgEkfNav- Computed navigation data. 
- /sbg/ekf_vel_bodysbg_driver/SbgEkfVelBody- Computed velocity expressed in the INS body/vehicle frame. 
- /sbg/ekf_rot_accel_bodysbg_driver/SbgEkfRotAccel- Computed rotations rate and accelerations in the INS body/vehicle frame. 
- /sbg/ekf_rot_accel_nedsbg_driver/SbgEkfRotAccel- Computed rotations rate and accelerations in North, East, Down (NED) navigation frame. 
- /sbg/magsbg_driver/SbgMag- Calibrated magnetic field measurement. 
- /sbg/mag_calibsbg_driver/SbgMagCalib- Magnetometer calibration data. 
- /sbg/ship_motionsbg_driver/SbgShipMotion- Heave, surge and sway data. 
- /sbg/gps_velsbg_driver/SbgGpsVel- GPS velocities from GPS receiver. 
- /sbg/gps_possbg_driver/SbgGpsPos- GPS positions from GPS receiver. 
- /sbg/gps_hdtsbg_driver/SbgGpsHdt- GPS true heading from dual antenna system. 
- /sbg/gps_rawsbg_driver/SbgGpsRaw- GPS raw data for post processing. 
- /sbg/odo_velsbg_driver/SbgOdoVel- Odometer velocity. 
- /sbg/event[ABCDE]sbg_driver/SbgEvent- Event on sync in the corresponding pin. 
- /sbg/pressuresbg_driver/SbgPressure- Pressure data. 
ROS2 standard topics
In order to define ROS2 standard topics, it requires sometimes several SBG messages, to be merged. For each ROS2 standard, you have to activate the needed SBG outputs.
- /imu/datasensor_msgs/Imu- IMU data. Requires - /sbg/imu_dataor- /sbg/imu_short. Optional (orientation)- /sbg/ekf_quat.
- /imu/tempsensor_msgs/Temperature- IMU temperature data. Requires - /sbg/imu_data.
- /imu/velocitygeometry_msgs/TwistStamped- IMU velocity data. Requires - /sbg/imu_data.
- /imu/magsensor_msgs/MagneticField- IMU magnetic field. Requires - /sbg/mag.
- /imu/pressensor_msgs/FluidPressure- IMU pressure data. Requires - /sbg/pressure.
- /imu/pos_ecefgeometry_msgs/PointStamped- Earth-Centered Earth-Fixed position. Requires - /sbg/ekf_nav.
- /imu/utc_refsensor_msgs/TimeReference- UTC time reference. Requires - /sbg/utc_time.
- /imu/nav_sat_fixsensor_msgs/NavSatFix- Navigation satellite fix for any Global Navigation Satellite System. Requires - /sbg/gps_pos.
- /imu/odometrynav_msgs/Odometry- UTM projected position relative to the first valid INS position. Requires - /sbg/imu_dataand- /sbg/ekv_navand either- /sbg/ekf_euleror- /sbg/ekf_quat. Disabled by default, set- odometry.enablein configuration file.
[!NOTE] Please update the driver configuration to enable standard ROS2 messages publication. Also, the driver only publish standard ROS2 messages if the driver is setup to use ENU frame convention.
NMEA topics
The driver can publish NMEA GGA messages from the internal GNSS receiver. It can be used with third party NTRIP client modules to support VRS networks providers.
Disabled by default, set nmea.publish to true in .yaml config file to use this feature.
- /ntrip_client/nmeanmea_msgs/Sentence- Data from - /sbg/gps_posserialized into NMEA GGA format. Requires- /sbg/gps_pos. Namespace- ntrip_clientand topic_name- nmeacan be customized in .yaml config files.
Subscribed Topics
RTCM topics
The sbg_device node can subscribe to RTCM topics published by third party ROS2 modules.
Incoming RTCM data are forwarded to the INS internal GNSS receiver to enable DGPS/RTK solutions.
Disabled by default, set rtcm.subscribe to true in .yaml config file to use this feature.
- /ntrip_client/rtcmrtcm_msgs/Message- RTCM data from - /ntrip_client/rtcmwill be forwarded to the internal INS GNSS receiver. Namespace- ntrip_clientand topic_name- rtcmcan be customized in .yaml config files.
sbg_device_mag node
The sbg_device_mag node is used to execute on board in-situ 2D or 3D magnetic field calibration. If you are planning to use magnetic based heading, it is mandatory to perform a magnetic field calibration in a clean magnetic environnement.
Only ELLIPSE products support magnetic based heading and feature the on-board magnetic field calibration process.
Services
- /sbg/mag_calibrationstd_srvs/Trigger- Service to start/stop the magnetic calibration. 
- /sbg/mag_calibration_savestd_srvs/Trigger- Service to save in FLASH memory the latest computed magnetic field calibration. 
HowTo
Configure the SBG device
The SBG ROS2 driver allows the user to configure the SBG device before starting data parsing. To do so, set the corresponding parameter in the used config file.
# Configuration of the device with ROS2.
confWithRos: true
Then, modify the desired parameters in the config file, using the Firmware Reference Manual, to see which features are configurable, and which parameter values are available.
[!NOTE] The confWithRos parameter will only impact the configuration of the SBG device sensor, not the configuration of the ROS2 drivers themselves. This means you can still configure RTCM corrections, reference frames, etc. when you set confWithRos to false. The confWithRos parameter must be disabled for HPI and pulse-40 products.
Configure for RTK/DGPS
The sbg_device node can subscribe to rtcm_msgs/Message topics to forward differential corrections to the INS internal GNSS receiver.
The RTCM data stream is sent through the serial/ethernet interface used by ROS2 to communicate with the INS. This enables simple and efficient RTK operations without requiring additional hardware or wiring.
When combined with a third party NTRIP client, it offers a turnkey solution to access local VRS providers and get centimeter-level accuracy solutions.
The driver and the device should be properly setup:
- Configure the INS to accept RTCM corrections on the interface used by the ROS2 driver: - For ELLIPSE, simply use the - sbgCenterand in- Assignment panel,- RTCMshould be set to- Port A.
- For High Performance INS, either use the configuration web interface or the sbgInsRestApi. 
 
- Install and configure a third party node that broadcast RTCM corrections such as a NTRIP client 
- Update the node config - yamlfile to set- rtcm.subscribeand- nmea.publishto- true
- If you use a different node to broadcast RTCM topics, you might have to update the config - yamlfile to update topics and namespaces.
Calibrate the magnetometers
ELLIPSE products can use magnetometers to determine the heading. A calibration is then required to compensate for soft and hard iron distortions due to the vehicle the product is installed on. The magnetic calibration procedure should be held in a clean magnetic environnement (outside of buildings).
You can read more information about magnetic field calibration procedure from the SBG Systems Support Center.
The ROS2 driver provides a dedicated node to easily use ELLIPSE on board magnetic field calibration algorithms. The ELLIPSE offers both a 2D and 3D magnetic field calibration mode.
- Make sure you have selected the desired 2D or 3D magnetic field calibration mode ( - calibration.modein the configuration- yamlfile).
- Start a new magnetic calibration session once you are ready to map the magnetic field: 
ros2 launch sbg_driver sbg_device_mag_calibration_launch.py
ros2 service call /sbg/mag_calibration std_srvs/srv/Trigger
response: std_srvs.srv.Trigger_Response(success=True, message=’Magnetometer calibration process started.’)
- Rotate as much as possible the unit to map the surrounding magnetic field (ideally, perform a 360° with X then Y then Z axis pointing downward). 
- Once you believe you have covered enough orientations, compute a magnetic field calibration: 
ros2 service call /sbg/mag_calibration std_srvs/srv/Trigger
response: std_srvs.srv.Trigger_Response(success=True, message=’Magnetometer calibration is finished. See the output console to get calibration information.’)
- If you are happy with the results (Quality, Confidence), apply and save the new magnetic calibration parameters. If not, you can continue to rotate the product and try to perform a new computation (and repeat step 4) 
ros2 service call /sbg/mag_calibration_save std_srvs/srv/Trigger
response: std_srvs.srv.Trigger_Response(success=True, message=’Magnetometer calibration has been uploaded to the device.’)
- Reset/Power Cycle the device and you should now get an accurate magnetic based heading. 
Enable communication with the SBG device
To be able to communicate with the device, be sure that your user is part of the dialout group. Once added, restart your machine to save and apply the changes.
sudo adduser $USER dialout
Create udev rules
Udev rules can be defined for communication port, in order to avoid modifying the port in configuration if it has changed. Udev documentation
A symlink can be configured and defined to uniquely identify the connected device.
Once it is done, configuration file could be updated portName: "/dev/sbg".
See the docs folder, to see an example of rules with the corresponding screenshot using the udev functions.
Time source & reference
ROS2 uses an internal system time to time stamp messages. This time stamp is generally gathered when the message is processed and published. As a result, the message is not time stamped accurately due to transmission and processing delays.
SBG Systems INS however provides a very accurate timing based on GNSS time if available. The following conditions have to be met to get absolute accurate timing information:
- The ELLIPSE-N or D should have a connected GNSS antenna with internal GNSS enabled 
- The ELLIPSE-E should be connected to an external GNSS receiver with a PPS signal 
- A valid GNSS position has to be available to get UTC data 
- The ELLIPSE internal clock should be aligned to PPS signal (clock status) 
- The ELLIPSE should be setup to send SBG_ECOM_LOG_UTC message 
You can select which time source to use with the parameter time_reference to time stamp messages published by this driver:
- ros: The header.stamp member contains the current ROS2 system time when the message has been processed.
- ins_unix: The header.stamp member contains an absolute and accurate time referenced to UNIX epoch (00:00:00 UTC on 1 January 1970)
Configuration example to use an absolute and accurate time reference to UNIX epoch:
# Time reference:
time_reference: "ins_unix"
Frame parameters & conventions
Frame ID
The frame_id of the header can be set with this parameter:
# Frame name
frame_id: "imu_link_ned"
[!NOTE] This parameter has not impact on the configuration and will be inserted as-is within the header field. The recommended default parameters for ros are imu_link when use_enu is activated, and imu_link_ned when use_enu is inactive. You can also use another frame_id as needed.
Frame convention
The frame convention can be set to NED or ENU:
- The NED convention is SBG Systems native convention so no transformation is applied 
- The ENU convention follows ROS2 standard REP-103 
Please read the SBG Systems Support Center article for more details.
You can select the frame convention to use with the following parameter:
# Frame convention
use_enu: true
[!NOTE] The driver only publish standard ROS2 messages if the driver is setup to use ENU frame convention.
Body/Vehicle Frame:
The X axis should point the vehicle forward direction for both NED and ENU frame conventions. The table below summarizes the body/vehicle axis frame definitions for each convention:
| NED Convention | ENU Convention | 
|---|---|
| X Forward | X Forward | 
| Y Right | Y Left | 
| Z Downward | Z Upward | 
Heading Example:
Based on the definitions above, when using a NED frame, if the vehicle X axis is pointing North, the INS should return a zero heading. When using a ENU frame, the INS should return a zero heading when the vehicle X axis is pointing East.
Troubleshooting
If you experience higher latency than expected and have connected the IMU via an USB interface, you can enable the serial driver low latency mode:
/bin/setserial /dev/<device> low_latency
Contributing
Bugs and issues
Please report bugs and/or issues using the Issue Tracker
Features requests or additions
In order to contribute to the code, please use Pull requests to the devel branch.
If you have some feature requests, use the Issue Tracker as well.
Known limitations
Baudrate configuration is not possible via ROS2 and can only be done in sbgCenter or using sbgECom library. Device information is not displayed for Pulse-40. GNSS and RTCM port configurations are not possible via ROS2.