sbg_driver package from sbg_driver reposbg_driver |
|
Package Summary
Tags | No category tags. |
Version | 3.2.0 |
License | MIT |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Checkout URI | https://github.com/SBG-Systems/sbg_ros2.git |
VCS Type | git |
VCS Version | master |
Last Updated | 2024-10-17 |
Dev Status | DEVELOPED |
CI status | No Continuous Integration |
Released | RELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- SBG Systems
Authors
- SBG Systems
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 the following features:
- Configure ELLIPSE products using yaml files (see note below)
- Parse IMU/AHRS/INS/GNSS using the sbgECom protocol
- Publish standard ROS 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
[!NOTE] Only ELLIPSE devices can be configured from the ROS driver. For High Performance INS such as EKINOX, APOGEE and QUANTA, please use the sbgInsRestApi
Installation
Installation from Packages
User can install the sbg_ros2_driver through the standard ROS installation system.
- Galactic
sudo apt-get install ros-galactic-sbg-driver
- Foxy
sudo apt-get install ros-foxy-sbg-driver
Building from sources
Dependencies
- Robot Operating System (ROS)
- 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 ROS 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
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 ROS node, so it has to be previously configured (manually or with the ROS node).
It defines a few outputs for the device:-
/sbg/imu_data
,/sbg/ekf_quat
at 25Hz - ROS standard outputs
/imu/data
,/imu/velocity
,/imu/temp
at 25Hz -
/sbg/status
,/sbg/utc_time
and/imu/utc_ref
at 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 ROS node, so it has to be previously configured (manually or with the ROS node).
It defines a few outputs for the device:-
/sbg/imu_data
,/sbg/ekf_quat
at 25Hz - ROS standard outputs
/imu/data
,/imu/velocity
,/imu/temp
at 25Hz -
/sbg/status
,/sbg/utc_time
and/imu/utc_ref
at 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.yaml
configuration. -
sbg_device_mag_calibration_launch.py Launch the sbg_device_mag node to calibrate the magnetometers, and load the
ellipse_E_default.yaml
configuration.
Nodes
sbg_device node
The sbg_device
node handles the communication with the connected device, publishes the SBG output to the Ros environment and subscribes to useful topics such as RTCM data streams.
Published Topics
SBG Systems specific topics
SBG Systems has defined proprietary ROS 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.
-
/sbg/status
sbg_driver/SbgStatusProvides information about the general status (Communication, Aiding, etc..).
-
/sbg/utc_time
sbg_driver/SbgUtcTimeProvides UTC time reference.
-
/sbg/imu_data
sbg_driver/SbgImuDataIMU status, and sensors values.
-
/sbg/ekf_euler
sbg_driver/SbgEkfEulerComputed orientation using Euler angles.
-
/sbg/ekf_quat
sbg_driver/SbgEkfQuatComputed orientation using Quaternion.
-
/sbg/ekf_nav
sbg_driver/SbgEkfNavComputed navigation data.
-
/sbg/ekf_vel_body
sbg_driver/SbgEkfVelBodyComputed velocity expressed in the INS body/vehicle frame.
-
/sbg/ekf_rot_accel_body
sbg_driver/SbgEkfRotAccelComputed rotations rate and accelerations in the INS body/vehicle frame.
-
/sbg/ekf_rot_accel_ned
sbg_driver/SbgEkfRotAccelComputed rotations rate and accelerations in North, East, Down (NED) navigation frame.
-
/sbg/mag
sbg_driver/SbgMagCalibrated magnetic field measurement.
-
/sbg/mag_calib
sbg_driver/SbgMagCalibMagnetometer calibration data.
-
/sbg/ship_motion
sbg_driver/SbgShipMotionHeave, surge and sway data.
-
/sbg/gps_vel
sbg_driver/SbgGpsVelGPS velocities from GPS receiver.
-
/sbg/gps_pos
sbg_driver/SbgGpsPosGPS positions from GPS receiver.
-
/sbg/gps_hdt
sbg_driver/SbgGpsHdtGPS true heading from dual antenna system.
-
/sbg/gps_raw
sbg_driver/SbgGpsRawGPS raw data for post processing.
-
/sbg/odo_vel
sbg_driver/SbgOdoVelOdometer velocity.
-
/sbg/event[ABCDE]
sbg_driver/SbgEventEvent on sync in the corresponding pin.
-
/sbg/pressure
sbg_driver/SbgPressurePressure data.
ROS standard topics
In order to define ROS standard topics, it requires sometimes several SBG messages, to be merged. For each ROS standard, you have to activate the needed SBG outputs.
-
/imu/data
sensor_msgs/ImuIMU data. Requires
/sbg/imu_data
and/sbg/ekf_quat
. -
/imu/temp
sensor_msgs/TemperatureIMU temperature data. Requires
/sbg/imu_data
. -
/imu/velocity
geometry_msgs/TwistStampedIMU velocity data. Requires
/sbg/imu_data
. -
/imu/mag
sensor_msgs/MagneticFieldIMU magnetic field. Requires
/sbg/mag
. -
/imu/pres
sensor_msgs/FluidPressureIMU pressure data. Requires
/sbg/pressure
. -
/imu/pos_ecef
geometry_msgs/PointStampedEarth-Centered Earth-Fixed position. Requires
/sbg/ekf_nav
. -
/imu/utc_ref
sensor_msgs/TimeReferenceUTC time reference. Requires
/sbg/utc_time
. -
/imu/nav_sat_fix
sensor_msgs/NavSatFixNavigation satellite fix for any Global Navigation Satellite System. Requires
/sbg/gps_pos
. -
/imu/odometry
nav_msgs/OdometryUTM projected position relative to the first valid INS position. Requires
/sbg/imu_data
and/sbg/ekv_nav
and either/sbg/ekf_euler
or/sbg/ekf_quat
. Disabled by default, setodometry.enable
in configuration file.
[!NOTE] Please update the driver configuration to enable standard ROS messages publication. Also, the driver only publish standard ROS 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/nmea
nmea_msgs/SentenceData from
/sbg/gps_pos
serialized into NMEA GGA format. Requires/sbg/gps_pos
.
Namespacentrip_client
and topic_namenmea
can 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/rtcm
rtcm_msgs/MessageRTCM data from
/ntrip_client/rtcm
will be forwarded to the internal INS GNSS receiver.
Namespacentrip_client
and topic_namertcm
can 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_calibration
std_srvs/TriggerService to start/stop the magnetic calibration.
-
/sbg/mag_calibration_save
std_srvs/TriggerService to save in FLASH memory the latest computed magnetic field calibration.
HowTo
Configure the SBG device
The SBG Ros driver allows the user to configure the device before starting data parsing.
To do so, set the corresponding parameter in the used config file.
# Configuration of the device with ROS.
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.
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 ROS 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 ROS driver:
- For ELLIPSE, simply use the
sbgCenter
and inAssignment panel
,RTCM
should be set toPort A
. - For High Performance INS, either use the configuration web interface or the sbgInsRestApi.
- For ELLIPSE, simply use the
- Install and configure a third party node that broadcast RTCM corrections such as a NTRIP client
- Update the node config
yaml
file to setrtcm.subscribe
andnmea.publish
totrue
- If you use a different node to broadcast RTCM topics, you might have to update the config
yaml
file 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 ROS 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.
1) Make sure you have selected the desired 2D or 3D magnetic field calibration mode (calibration.mode
in the configuration yaml
file).
2) 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.’)
3) 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). 4) 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.’)
5) 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.’)
6) 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
ROS 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 ROS 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"
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 ROS 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 ROS 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 |
Navigation Frame:
The navigation frame also referred by ROS as the cartesian representation is defined as follow:
NED Convention | ENU Convention |
---|---|
X North | X East |
Y East | Y North |
Z Down | Z Up |
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.
Changelog for package sbg_driver
3.2.0 (2024-10-17)
- Update README with ROS2 commands to launch magnetic calibration
- Fix segfault when running magnetic calibration
- Removed unused flags from SbgEkfStatus message
- Added new flags to SbgShipMotionStatus message
- Improved SbgStatusAiding message with new flags
- Improved SbgPosStatus message with new flags
- Improved SbgEkfStatus message with new flags
- Improved SbgStatusGeneral message with datalogger and cpu flags
- Updated documentation for sbgGpsPos message
- Updated documentation for sbgGpsHdt message
- Improved SbgUtcTime message with internal clock quality indicators
- Improved SbgStatusCom message with ethernet tx and rx status
- Improved SbgGpsHdt message with number of SV tracked and used
- Improved SbgGpsPos message with numSvTracked
- Improved SbgGpsPosStatus message with spoofing, jamming and OSNMA status
- Updated config files with new messages
- Removed obsolete documentation
- Updated published topic list
- Added missing topic names
- Updated dependencies requirement
- Added settings log_ekf_rot_accel_body / log_ekf_rot_accel_ned / log_ekf_vel_body
- Fixed functions description
- Added SbgEkfRotAccel body and NED messages
- Added SbgEkfVelBody message
- Fixing compiling issues
- Updated sbgECom lib with version 4.0-1987-stable
- Fixed typos about lever arm
- Fixed config applier for IMU Alignment / Aiding / Odometer lever arms
- Remove boost dependency (cherry picked from commit ab54c33f1e442c3737dd8e1c09a8b6f36c2c1afa)
- Cleanup
- Moved LLAtoECEF into a helper
- Variable naming
- WIP code cleanup
- Class documentation
- Code indentation
- Utm as class
- Indentation fix
- Updated sbg_utm documentation and function prototype
- Added documentation on Utm structure
- Added documentation on Position class
- Added Position class
- Factory for UTM data
- Fixed space / tabluations issues
- Code indentation
- SbgUtm documentation
- Using fma for computation
- Added constexpr to some variables
- Using pow instead of multiply
- Reworked createRosPointStampedMessage computations
- Removed sendTransform in fillTransform method
- Moved functions into helper namespace
- Moved UTM initialization into its own class
- Removed catkin reference in CMakeLists.txt
- Updated naming convention
- Improved ENU/NED documentation
- Disabling ROS standard message when in NED frame convention
- Reverted NED to ENU quaternion conversion
- Quaternion: cleaner version for NED to ENU conversion
- Reworked odometry message
- Quaternion: NED to ENU conversion rework
- Updated readme about ENU frame convention
- Reworked angle wrapping functions
- Added range for Euler angle measurement.
- More explicit naming for quaternions
- Reverted NED to ENU array conversion
- Documentation update
- odom->base_link is now correct in NED mode
- Renamed function.
- Fixed variable inversion.
- odom->base_link is now correct in NED mode
- Refactored NED to ENU array conversion
- Updated ROS messages documentation
- Fixed Euler / Quaternion orientation in ENU mode
- Fixed nmea output condition
- Compilation fixes
- NTRIP: GGA generation Work In Progress with the following fixex:
- GPS to UTC time correctly apply leap second offset
- GGA only sent if a valid position is available
- GGA is sent at 1 Hz only
- Minor improvements Code is not yet tested nor build
- Compilation fix
- Improved GGA generation and code cleanup
- Improved RTCM and NMEA parameters naming
- Code cleanup - removed (void) as it is not recommended in C++
- Reworked and improved main project README and small fixed in yaml examples
- Added documentation about RTCM messages and device configuration.
- Removed MessageSubscriber class
- Switched dependency from mavros_msgs to rtcm_msgs
- Updated documentation
- Removed SbgInterface as class member
- Removed threaded subscription.
- Namespace related coding style fix
- Fixes in GGA serialization
- Realigned members.
- Code documentation
- Improved NMEA GGA message
- Added rtcm / nmea parameters in config files
- Fixed deprecated header warning
- Added publisher for nmea msg
- Added subscription to RTCM msg
- remove build status
- fix build on Windows
- time_reference parameter fix
- Fix deprecated use of rosidl_target_interfaces The use of rosidl_target_interfaces is deprecated (see [Humble release notes](http://docs.ros.org.ros.informatik.uni-freiburg.de/en/humble/Releases/Release-Humble-Hawksbill.html#deprecation-of-rosidl-target-interfaces). Here that actually causes an issue with CMake not setting the right include directory paths, breaking [colcon build]{.title-ref} on humble. This applies the documented update, making the driver build under Humble
- Contributors: Michael Zemb, Raphael Siryani, Samuel Toledano, SanderVanDijk-StreetDrone, Timon Mentink, VladimirL, cledant, rsiryani
3.1.0 (2021-10-18)
- Add imu/odometry publisher
- Fix dependencies
- Fix wrong SbgGpsHdt description
- Update doc
- Add missing MIT licences
- Based on release 3.1 of ros1 driver
- Add ENU/NED option, rework frame IDs, time stamps and driver
frequency.
- Add parameters to set frame ID and ENU convention
- Add a parameter to select header stamp source and read ROS time when publishing the message
- Remove node ros::Rate period auto computation and only read it from a node parameter
- Update documentation and messages definitions
- Fix timeStamp value initializing in SbgEkfNavMessage
- Based on release 3.0.0 of ros1 driver
- update maintainer
- print interface details at startup
- fix configuration files
- Contributors: Michael Zemb, Raphael Siryani
1.0.1 (2020-07-09)
- Update Licenses
- First version
Wiki Tutorials
Package Dependencies
Deps | Name |
---|---|
ament_cmake | |
rosidl_default_generators | |
rosidl_default_runtime | |
geometry_msgs | |
rclcpp | |
sensor_msgs | |
std_msgs | |
std_srvs | |
nav_msgs | |
rtcm_msgs | |
tf2_ros | |
tf2_msgs | |
tf2_geometry_msgs | |
nmea_msgs |
System Dependencies
Dependant Packages
Launch files
Messages
- msg/SbgEkfQuat.msg
- msg/SbgStatusCom.msg
- msg/SbgGpsVel.msg
- msg/SbgMag.msg
- msg/SbgShipMotionStatus.msg
- msg/SbgImuData.msg
- msg/SbgUtcTimeStatus.msg
- msg/SbgShipMotion.msg
- msg/SbgGpsPosStatus.msg
- msg/SbgImuStatus.msg
- msg/SbgStatus.msg
- msg/SbgStatusAiding.msg
- msg/SbgUtcTime.msg
- msg/SbgAirDataStatus.msg
- msg/SbgEkfNav.msg
- msg/SbgEkfEuler.msg
- msg/SbgMagCalib.msg
- msg/SbgGpsRaw.msg
- msg/SbgGpsHdt.msg
- msg/SbgEkfStatus.msg
- msg/SbgStatusGeneral.msg
- msg/SbgGpsPos.msg
- msg/SbgAirData.msg
- msg/SbgEkfRotAccel.msg
- msg/SbgMagStatus.msg
- msg/SbgOdoVel.msg
- msg/SbgImuShort.msg
- msg/SbgGpsVelStatus.msg
- msg/SbgEkfVelBody.msg
- msg/SbgEvent.msg
Services
Plugins
Recent questions tagged sbg_driver at Robotics Stack Exchange
sbg_driver package from sbg_driver reposbg_driver |
|
Package Summary
Tags | No category tags. |
Version | 3.2.0 |
License | MIT |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Checkout URI | https://github.com/SBG-Systems/sbg_ros2.git |
VCS Type | git |
VCS Version | master |
Last Updated | 2024-10-17 |
Dev Status | DEVELOPED |
CI status | No Continuous Integration |
Released | RELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- SBG Systems
Authors
- SBG Systems
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 the following features:
- Configure ELLIPSE products using yaml files (see note below)
- Parse IMU/AHRS/INS/GNSS using the sbgECom protocol
- Publish standard ROS 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
[!NOTE] Only ELLIPSE devices can be configured from the ROS driver. For High Performance INS such as EKINOX, APOGEE and QUANTA, please use the sbgInsRestApi
Installation
Installation from Packages
User can install the sbg_ros2_driver through the standard ROS installation system.
- Galactic
sudo apt-get install ros-galactic-sbg-driver
- Foxy
sudo apt-get install ros-foxy-sbg-driver
Building from sources
Dependencies
- Robot Operating System (ROS)
- 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 ROS 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
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 ROS node, so it has to be previously configured (manually or with the ROS node).
It defines a few outputs for the device:-
/sbg/imu_data
,/sbg/ekf_quat
at 25Hz - ROS standard outputs
/imu/data
,/imu/velocity
,/imu/temp
at 25Hz -
/sbg/status
,/sbg/utc_time
and/imu/utc_ref
at 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 ROS node, so it has to be previously configured (manually or with the ROS node).
It defines a few outputs for the device:-
/sbg/imu_data
,/sbg/ekf_quat
at 25Hz - ROS standard outputs
/imu/data
,/imu/velocity
,/imu/temp
at 25Hz -
/sbg/status
,/sbg/utc_time
and/imu/utc_ref
at 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.yaml
configuration. -
sbg_device_mag_calibration_launch.py Launch the sbg_device_mag node to calibrate the magnetometers, and load the
ellipse_E_default.yaml
configuration.
Nodes
sbg_device node
The sbg_device
node handles the communication with the connected device, publishes the SBG output to the Ros environment and subscribes to useful topics such as RTCM data streams.
Published Topics
SBG Systems specific topics
SBG Systems has defined proprietary ROS 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.
-
/sbg/status
sbg_driver/SbgStatusProvides information about the general status (Communication, Aiding, etc..).
-
/sbg/utc_time
sbg_driver/SbgUtcTimeProvides UTC time reference.
-
/sbg/imu_data
sbg_driver/SbgImuDataIMU status, and sensors values.
-
/sbg/ekf_euler
sbg_driver/SbgEkfEulerComputed orientation using Euler angles.
-
/sbg/ekf_quat
sbg_driver/SbgEkfQuatComputed orientation using Quaternion.
-
/sbg/ekf_nav
sbg_driver/SbgEkfNavComputed navigation data.
-
/sbg/ekf_vel_body
sbg_driver/SbgEkfVelBodyComputed velocity expressed in the INS body/vehicle frame.
-
/sbg/ekf_rot_accel_body
sbg_driver/SbgEkfRotAccelComputed rotations rate and accelerations in the INS body/vehicle frame.
-
/sbg/ekf_rot_accel_ned
sbg_driver/SbgEkfRotAccelComputed rotations rate and accelerations in North, East, Down (NED) navigation frame.
-
/sbg/mag
sbg_driver/SbgMagCalibrated magnetic field measurement.
-
/sbg/mag_calib
sbg_driver/SbgMagCalibMagnetometer calibration data.
-
/sbg/ship_motion
sbg_driver/SbgShipMotionHeave, surge and sway data.
-
/sbg/gps_vel
sbg_driver/SbgGpsVelGPS velocities from GPS receiver.
-
/sbg/gps_pos
sbg_driver/SbgGpsPosGPS positions from GPS receiver.
-
/sbg/gps_hdt
sbg_driver/SbgGpsHdtGPS true heading from dual antenna system.
-
/sbg/gps_raw
sbg_driver/SbgGpsRawGPS raw data for post processing.
-
/sbg/odo_vel
sbg_driver/SbgOdoVelOdometer velocity.
-
/sbg/event[ABCDE]
sbg_driver/SbgEventEvent on sync in the corresponding pin.
-
/sbg/pressure
sbg_driver/SbgPressurePressure data.
ROS standard topics
In order to define ROS standard topics, it requires sometimes several SBG messages, to be merged. For each ROS standard, you have to activate the needed SBG outputs.
-
/imu/data
sensor_msgs/ImuIMU data. Requires
/sbg/imu_data
and/sbg/ekf_quat
. -
/imu/temp
sensor_msgs/TemperatureIMU temperature data. Requires
/sbg/imu_data
. -
/imu/velocity
geometry_msgs/TwistStampedIMU velocity data. Requires
/sbg/imu_data
. -
/imu/mag
sensor_msgs/MagneticFieldIMU magnetic field. Requires
/sbg/mag
. -
/imu/pres
sensor_msgs/FluidPressureIMU pressure data. Requires
/sbg/pressure
. -
/imu/pos_ecef
geometry_msgs/PointStampedEarth-Centered Earth-Fixed position. Requires
/sbg/ekf_nav
. -
/imu/utc_ref
sensor_msgs/TimeReferenceUTC time reference. Requires
/sbg/utc_time
. -
/imu/nav_sat_fix
sensor_msgs/NavSatFixNavigation satellite fix for any Global Navigation Satellite System. Requires
/sbg/gps_pos
. -
/imu/odometry
nav_msgs/OdometryUTM projected position relative to the first valid INS position. Requires
/sbg/imu_data
and/sbg/ekv_nav
and either/sbg/ekf_euler
or/sbg/ekf_quat
. Disabled by default, setodometry.enable
in configuration file.
[!NOTE] Please update the driver configuration to enable standard ROS messages publication. Also, the driver only publish standard ROS 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/nmea
nmea_msgs/SentenceData from
/sbg/gps_pos
serialized into NMEA GGA format. Requires/sbg/gps_pos
.
Namespacentrip_client
and topic_namenmea
can 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/rtcm
rtcm_msgs/MessageRTCM data from
/ntrip_client/rtcm
will be forwarded to the internal INS GNSS receiver.
Namespacentrip_client
and topic_namertcm
can 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_calibration
std_srvs/TriggerService to start/stop the magnetic calibration.
-
/sbg/mag_calibration_save
std_srvs/TriggerService to save in FLASH memory the latest computed magnetic field calibration.
HowTo
Configure the SBG device
The SBG Ros driver allows the user to configure the device before starting data parsing.
To do so, set the corresponding parameter in the used config file.
# Configuration of the device with ROS.
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.
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 ROS 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 ROS driver:
- For ELLIPSE, simply use the
sbgCenter
and inAssignment panel
,RTCM
should be set toPort A
. - For High Performance INS, either use the configuration web interface or the sbgInsRestApi.
- For ELLIPSE, simply use the
- Install and configure a third party node that broadcast RTCM corrections such as a NTRIP client
- Update the node config
yaml
file to setrtcm.subscribe
andnmea.publish
totrue
- If you use a different node to broadcast RTCM topics, you might have to update the config
yaml
file 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 ROS 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.
1) Make sure you have selected the desired 2D or 3D magnetic field calibration mode (calibration.mode
in the configuration yaml
file).
2) 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.’)
3) 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). 4) 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.’)
5) 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.’)
6) 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
ROS 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 ROS 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"
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 ROS 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 ROS 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 |
Navigation Frame:
The navigation frame also referred by ROS as the cartesian representation is defined as follow:
NED Convention | ENU Convention |
---|---|
X North | X East |
Y East | Y North |
Z Down | Z Up |
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.
Changelog for package sbg_driver
3.2.0 (2024-10-17)
- Update README with ROS2 commands to launch magnetic calibration
- Fix segfault when running magnetic calibration
- Removed unused flags from SbgEkfStatus message
- Added new flags to SbgShipMotionStatus message
- Improved SbgStatusAiding message with new flags
- Improved SbgPosStatus message with new flags
- Improved SbgEkfStatus message with new flags
- Improved SbgStatusGeneral message with datalogger and cpu flags
- Updated documentation for sbgGpsPos message
- Updated documentation for sbgGpsHdt message
- Improved SbgUtcTime message with internal clock quality indicators
- Improved SbgStatusCom message with ethernet tx and rx status
- Improved SbgGpsHdt message with number of SV tracked and used
- Improved SbgGpsPos message with numSvTracked
- Improved SbgGpsPosStatus message with spoofing, jamming and OSNMA status
- Updated config files with new messages
- Removed obsolete documentation
- Updated published topic list
- Added missing topic names
- Updated dependencies requirement
- Added settings log_ekf_rot_accel_body / log_ekf_rot_accel_ned / log_ekf_vel_body
- Fixed functions description
- Added SbgEkfRotAccel body and NED messages
- Added SbgEkfVelBody message
- Fixing compiling issues
- Updated sbgECom lib with version 4.0-1987-stable
- Fixed typos about lever arm
- Fixed config applier for IMU Alignment / Aiding / Odometer lever arms
- Remove boost dependency (cherry picked from commit ab54c33f1e442c3737dd8e1c09a8b6f36c2c1afa)
- Cleanup
- Moved LLAtoECEF into a helper
- Variable naming
- WIP code cleanup
- Class documentation
- Code indentation
- Utm as class
- Indentation fix
- Updated sbg_utm documentation and function prototype
- Added documentation on Utm structure
- Added documentation on Position class
- Added Position class
- Factory for UTM data
- Fixed space / tabluations issues
- Code indentation
- SbgUtm documentation
- Using fma for computation
- Added constexpr to some variables
- Using pow instead of multiply
- Reworked createRosPointStampedMessage computations
- Removed sendTransform in fillTransform method
- Moved functions into helper namespace
- Moved UTM initialization into its own class
- Removed catkin reference in CMakeLists.txt
- Updated naming convention
- Improved ENU/NED documentation
- Disabling ROS standard message when in NED frame convention
- Reverted NED to ENU quaternion conversion
- Quaternion: cleaner version for NED to ENU conversion
- Reworked odometry message
- Quaternion: NED to ENU conversion rework
- Updated readme about ENU frame convention
- Reworked angle wrapping functions
- Added range for Euler angle measurement.
- More explicit naming for quaternions
- Reverted NED to ENU array conversion
- Documentation update
- odom->base_link is now correct in NED mode
- Renamed function.
- Fixed variable inversion.
- odom->base_link is now correct in NED mode
- Refactored NED to ENU array conversion
- Updated ROS messages documentation
- Fixed Euler / Quaternion orientation in ENU mode
- Fixed nmea output condition
- Compilation fixes
- NTRIP: GGA generation Work In Progress with the following fixex:
- GPS to UTC time correctly apply leap second offset
- GGA only sent if a valid position is available
- GGA is sent at 1 Hz only
- Minor improvements Code is not yet tested nor build
- Compilation fix
- Improved GGA generation and code cleanup
- Improved RTCM and NMEA parameters naming
- Code cleanup - removed (void) as it is not recommended in C++
- Reworked and improved main project README and small fixed in yaml examples
- Added documentation about RTCM messages and device configuration.
- Removed MessageSubscriber class
- Switched dependency from mavros_msgs to rtcm_msgs
- Updated documentation
- Removed SbgInterface as class member
- Removed threaded subscription.
- Namespace related coding style fix
- Fixes in GGA serialization
- Realigned members.
- Code documentation
- Improved NMEA GGA message
- Added rtcm / nmea parameters in config files
- Fixed deprecated header warning
- Added publisher for nmea msg
- Added subscription to RTCM msg
- remove build status
- fix build on Windows
- time_reference parameter fix
- Fix deprecated use of rosidl_target_interfaces The use of rosidl_target_interfaces is deprecated (see [Humble release notes](http://docs.ros.org.ros.informatik.uni-freiburg.de/en/humble/Releases/Release-Humble-Hawksbill.html#deprecation-of-rosidl-target-interfaces). Here that actually causes an issue with CMake not setting the right include directory paths, breaking [colcon build]{.title-ref} on humble. This applies the documented update, making the driver build under Humble
- Contributors: Michael Zemb, Raphael Siryani, Samuel Toledano, SanderVanDijk-StreetDrone, Timon Mentink, VladimirL, cledant, rsiryani
3.1.0 (2021-10-18)
- Add imu/odometry publisher
- Fix dependencies
- Fix wrong SbgGpsHdt description
- Update doc
- Add missing MIT licences
- Based on release 3.1 of ros1 driver
- Add ENU/NED option, rework frame IDs, time stamps and driver
frequency.
- Add parameters to set frame ID and ENU convention
- Add a parameter to select header stamp source and read ROS time when publishing the message
- Remove node ros::Rate period auto computation and only read it from a node parameter
- Update documentation and messages definitions
- Fix timeStamp value initializing in SbgEkfNavMessage
- Based on release 3.0.0 of ros1 driver
- update maintainer
- print interface details at startup
- fix configuration files
- Contributors: Michael Zemb, Raphael Siryani
1.0.1 (2020-07-09)
- Update Licenses
- First version
Wiki Tutorials
Package Dependencies
Deps | Name |
---|---|
ament_cmake | |
rosidl_default_generators | |
rosidl_default_runtime | |
geometry_msgs | |
rclcpp | |
sensor_msgs | |
std_msgs | |
std_srvs | |
nav_msgs | |
rtcm_msgs | |
tf2_ros | |
tf2_msgs | |
tf2_geometry_msgs | |
nmea_msgs |
System Dependencies
Dependant Packages
Launch files
Messages
- msg/SbgEkfQuat.msg
- msg/SbgStatusCom.msg
- msg/SbgGpsVel.msg
- msg/SbgMag.msg
- msg/SbgShipMotionStatus.msg
- msg/SbgImuData.msg
- msg/SbgUtcTimeStatus.msg
- msg/SbgShipMotion.msg
- msg/SbgGpsPosStatus.msg
- msg/SbgImuStatus.msg
- msg/SbgStatus.msg
- msg/SbgStatusAiding.msg
- msg/SbgUtcTime.msg
- msg/SbgAirDataStatus.msg
- msg/SbgEkfNav.msg
- msg/SbgEkfEuler.msg
- msg/SbgMagCalib.msg
- msg/SbgGpsRaw.msg
- msg/SbgGpsHdt.msg
- msg/SbgEkfStatus.msg
- msg/SbgStatusGeneral.msg
- msg/SbgGpsPos.msg
- msg/SbgAirData.msg
- msg/SbgEkfRotAccel.msg
- msg/SbgMagStatus.msg
- msg/SbgOdoVel.msg
- msg/SbgImuShort.msg
- msg/SbgGpsVelStatus.msg
- msg/SbgEkfVelBody.msg
- msg/SbgEvent.msg
Services
Plugins
Recent questions tagged sbg_driver at Robotics Stack Exchange
sbg_driver package from sbg_driver reposbg_driver |
|
Package Summary
Tags | No category tags. |
Version | 3.2.0 |
License | MIT |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Checkout URI | https://github.com/SBG-Systems/sbg_ros2.git |
VCS Type | git |
VCS Version | master |
Last Updated | 2024-10-17 |
Dev Status | DEVELOPED |
CI status | No Continuous Integration |
Released | RELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- SBG Systems
Authors
- SBG Systems
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 the following features:
- Configure ELLIPSE products using yaml files (see note below)
- Parse IMU/AHRS/INS/GNSS using the sbgECom protocol
- Publish standard ROS 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
[!NOTE] Only ELLIPSE devices can be configured from the ROS driver. For High Performance INS such as EKINOX, APOGEE and QUANTA, please use the sbgInsRestApi
Installation
Installation from Packages
User can install the sbg_ros2_driver through the standard ROS installation system.
- Galactic
sudo apt-get install ros-galactic-sbg-driver
- Foxy
sudo apt-get install ros-foxy-sbg-driver
Building from sources
Dependencies
- Robot Operating System (ROS)
- 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 ROS 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
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 ROS node, so it has to be previously configured (manually or with the ROS node).
It defines a few outputs for the device:-
/sbg/imu_data
,/sbg/ekf_quat
at 25Hz - ROS standard outputs
/imu/data
,/imu/velocity
,/imu/temp
at 25Hz -
/sbg/status
,/sbg/utc_time
and/imu/utc_ref
at 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 ROS node, so it has to be previously configured (manually or with the ROS node).
It defines a few outputs for the device:-
/sbg/imu_data
,/sbg/ekf_quat
at 25Hz - ROS standard outputs
/imu/data
,/imu/velocity
,/imu/temp
at 25Hz -
/sbg/status
,/sbg/utc_time
and/imu/utc_ref
at 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.yaml
configuration. -
sbg_device_mag_calibration_launch.py Launch the sbg_device_mag node to calibrate the magnetometers, and load the
ellipse_E_default.yaml
configuration.
Nodes
sbg_device node
The sbg_device
node handles the communication with the connected device, publishes the SBG output to the Ros environment and subscribes to useful topics such as RTCM data streams.
Published Topics
SBG Systems specific topics
SBG Systems has defined proprietary ROS 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.
-
/sbg/status
sbg_driver/SbgStatusProvides information about the general status (Communication, Aiding, etc..).
-
/sbg/utc_time
sbg_driver/SbgUtcTimeProvides UTC time reference.
-
/sbg/imu_data
sbg_driver/SbgImuDataIMU status, and sensors values.
-
/sbg/ekf_euler
sbg_driver/SbgEkfEulerComputed orientation using Euler angles.
-
/sbg/ekf_quat
sbg_driver/SbgEkfQuatComputed orientation using Quaternion.
-
/sbg/ekf_nav
sbg_driver/SbgEkfNavComputed navigation data.
-
/sbg/ekf_vel_body
sbg_driver/SbgEkfVelBodyComputed velocity expressed in the INS body/vehicle frame.
-
/sbg/ekf_rot_accel_body
sbg_driver/SbgEkfRotAccelComputed rotations rate and accelerations in the INS body/vehicle frame.
-
/sbg/ekf_rot_accel_ned
sbg_driver/SbgEkfRotAccelComputed rotations rate and accelerations in North, East, Down (NED) navigation frame.
-
/sbg/mag
sbg_driver/SbgMagCalibrated magnetic field measurement.
-
/sbg/mag_calib
sbg_driver/SbgMagCalibMagnetometer calibration data.
-
/sbg/ship_motion
sbg_driver/SbgShipMotionHeave, surge and sway data.
-
/sbg/gps_vel
sbg_driver/SbgGpsVelGPS velocities from GPS receiver.
-
/sbg/gps_pos
sbg_driver/SbgGpsPosGPS positions from GPS receiver.
-
/sbg/gps_hdt
sbg_driver/SbgGpsHdtGPS true heading from dual antenna system.
-
/sbg/gps_raw
sbg_driver/SbgGpsRawGPS raw data for post processing.
-
/sbg/odo_vel
sbg_driver/SbgOdoVelOdometer velocity.
-
/sbg/event[ABCDE]
sbg_driver/SbgEventEvent on sync in the corresponding pin.
-
/sbg/pressure
sbg_driver/SbgPressurePressure data.
ROS standard topics
In order to define ROS standard topics, it requires sometimes several SBG messages, to be merged. For each ROS standard, you have to activate the needed SBG outputs.
-
/imu/data
sensor_msgs/ImuIMU data. Requires
/sbg/imu_data
and/sbg/ekf_quat
. -
/imu/temp
sensor_msgs/TemperatureIMU temperature data. Requires
/sbg/imu_data
. -
/imu/velocity
geometry_msgs/TwistStampedIMU velocity data. Requires
/sbg/imu_data
. -
/imu/mag
sensor_msgs/MagneticFieldIMU magnetic field. Requires
/sbg/mag
. -
/imu/pres
sensor_msgs/FluidPressureIMU pressure data. Requires
/sbg/pressure
. -
/imu/pos_ecef
geometry_msgs/PointStampedEarth-Centered Earth-Fixed position. Requires
/sbg/ekf_nav
. -
/imu/utc_ref
sensor_msgs/TimeReferenceUTC time reference. Requires
/sbg/utc_time
. -
/imu/nav_sat_fix
sensor_msgs/NavSatFixNavigation satellite fix for any Global Navigation Satellite System. Requires
/sbg/gps_pos
. -
/imu/odometry
nav_msgs/OdometryUTM projected position relative to the first valid INS position. Requires
/sbg/imu_data
and/sbg/ekv_nav
and either/sbg/ekf_euler
or/sbg/ekf_quat
. Disabled by default, setodometry.enable
in configuration file.
[!NOTE] Please update the driver configuration to enable standard ROS messages publication. Also, the driver only publish standard ROS 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/nmea
nmea_msgs/SentenceData from
/sbg/gps_pos
serialized into NMEA GGA format. Requires/sbg/gps_pos
.
Namespacentrip_client
and topic_namenmea
can 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/rtcm
rtcm_msgs/MessageRTCM data from
/ntrip_client/rtcm
will be forwarded to the internal INS GNSS receiver.
Namespacentrip_client
and topic_namertcm
can 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_calibration
std_srvs/TriggerService to start/stop the magnetic calibration.
-
/sbg/mag_calibration_save
std_srvs/TriggerService to save in FLASH memory the latest computed magnetic field calibration.
HowTo
Configure the SBG device
The SBG Ros driver allows the user to configure the device before starting data parsing.
To do so, set the corresponding parameter in the used config file.
# Configuration of the device with ROS.
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.
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 ROS 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 ROS driver:
- For ELLIPSE, simply use the
sbgCenter
and inAssignment panel
,RTCM
should be set toPort A
. - For High Performance INS, either use the configuration web interface or the sbgInsRestApi.
- For ELLIPSE, simply use the
- Install and configure a third party node that broadcast RTCM corrections such as a NTRIP client
- Update the node config
yaml
file to setrtcm.subscribe
andnmea.publish
totrue
- If you use a different node to broadcast RTCM topics, you might have to update the config
yaml
file 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 ROS 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.
1) Make sure you have selected the desired 2D or 3D magnetic field calibration mode (calibration.mode
in the configuration yaml
file).
2) 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.’)
3) 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). 4) 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.’)
5) 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.’)
6) 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
ROS 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 ROS 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"
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 ROS 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 ROS 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 |
Navigation Frame:
The navigation frame also referred by ROS as the cartesian representation is defined as follow:
NED Convention | ENU Convention |
---|---|
X North | X East |
Y East | Y North |
Z Down | Z Up |
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.
Changelog for package sbg_driver
3.2.0 (2024-10-17)
- Update README with ROS2 commands to launch magnetic calibration
- Fix segfault when running magnetic calibration
- Removed unused flags from SbgEkfStatus message
- Added new flags to SbgShipMotionStatus message
- Improved SbgStatusAiding message with new flags
- Improved SbgPosStatus message with new flags
- Improved SbgEkfStatus message with new flags
- Improved SbgStatusGeneral message with datalogger and cpu flags
- Updated documentation for sbgGpsPos message
- Updated documentation for sbgGpsHdt message
- Improved SbgUtcTime message with internal clock quality indicators
- Improved SbgStatusCom message with ethernet tx and rx status
- Improved SbgGpsHdt message with number of SV tracked and used
- Improved SbgGpsPos message with numSvTracked
- Improved SbgGpsPosStatus message with spoofing, jamming and OSNMA status
- Updated config files with new messages
- Removed obsolete documentation
- Updated published topic list
- Added missing topic names
- Updated dependencies requirement
- Added settings log_ekf_rot_accel_body / log_ekf_rot_accel_ned / log_ekf_vel_body
- Fixed functions description
- Added SbgEkfRotAccel body and NED messages
- Added SbgEkfVelBody message
- Fixing compiling issues
- Updated sbgECom lib with version 4.0-1987-stable
- Fixed typos about lever arm
- Fixed config applier for IMU Alignment / Aiding / Odometer lever arms
- Remove boost dependency (cherry picked from commit ab54c33f1e442c3737dd8e1c09a8b6f36c2c1afa)
- Cleanup
- Moved LLAtoECEF into a helper
- Variable naming
- WIP code cleanup
- Class documentation
- Code indentation
- Utm as class
- Indentation fix
- Updated sbg_utm documentation and function prototype
- Added documentation on Utm structure
- Added documentation on Position class
- Added Position class
- Factory for UTM data
- Fixed space / tabluations issues
- Code indentation
- SbgUtm documentation
- Using fma for computation
- Added constexpr to some variables
- Using pow instead of multiply
- Reworked createRosPointStampedMessage computations
- Removed sendTransform in fillTransform method
- Moved functions into helper namespace
- Moved UTM initialization into its own class
- Removed catkin reference in CMakeLists.txt
- Updated naming convention
- Improved ENU/NED documentation
- Disabling ROS standard message when in NED frame convention
- Reverted NED to ENU quaternion conversion
- Quaternion: cleaner version for NED to ENU conversion
- Reworked odometry message
- Quaternion: NED to ENU conversion rework
- Updated readme about ENU frame convention
- Reworked angle wrapping functions
- Added range for Euler angle measurement.
- More explicit naming for quaternions
- Reverted NED to ENU array conversion
- Documentation update
- odom->base_link is now correct in NED mode
- Renamed function.
- Fixed variable inversion.
- odom->base_link is now correct in NED mode
- Refactored NED to ENU array conversion
- Updated ROS messages documentation
- Fixed Euler / Quaternion orientation in ENU mode
- Fixed nmea output condition
- Compilation fixes
- NTRIP: GGA generation Work In Progress with the following fixex:
- GPS to UTC time correctly apply leap second offset
- GGA only sent if a valid position is available
- GGA is sent at 1 Hz only
- Minor improvements Code is not yet tested nor build
- Compilation fix
- Improved GGA generation and code cleanup
- Improved RTCM and NMEA parameters naming
- Code cleanup - removed (void) as it is not recommended in C++
- Reworked and improved main project README and small fixed in yaml examples
- Added documentation about RTCM messages and device configuration.
- Removed MessageSubscriber class
- Switched dependency from mavros_msgs to rtcm_msgs
- Updated documentation
- Removed SbgInterface as class member
- Removed threaded subscription.
- Namespace related coding style fix
- Fixes in GGA serialization
- Realigned members.
- Code documentation
- Improved NMEA GGA message
- Added rtcm / nmea parameters in config files
- Fixed deprecated header warning
- Added publisher for nmea msg
- Added subscription to RTCM msg
- remove build status
- fix build on Windows
- time_reference parameter fix
- Fix deprecated use of rosidl_target_interfaces The use of rosidl_target_interfaces is deprecated (see [Humble release notes](http://docs.ros.org.ros.informatik.uni-freiburg.de/en/humble/Releases/Release-Humble-Hawksbill.html#deprecation-of-rosidl-target-interfaces). Here that actually causes an issue with CMake not setting the right include directory paths, breaking [colcon build]{.title-ref} on humble. This applies the documented update, making the driver build under Humble
- Contributors: Michael Zemb, Raphael Siryani, Samuel Toledano, SanderVanDijk-StreetDrone, Timon Mentink, VladimirL, cledant, rsiryani
3.1.0 (2021-10-18)
- Add imu/odometry publisher
- Fix dependencies
- Fix wrong SbgGpsHdt description
- Update doc
- Add missing MIT licences
- Based on release 3.1 of ros1 driver
- Add ENU/NED option, rework frame IDs, time stamps and driver
frequency.
- Add parameters to set frame ID and ENU convention
- Add a parameter to select header stamp source and read ROS time when publishing the message
- Remove node ros::Rate period auto computation and only read it from a node parameter
- Update documentation and messages definitions
- Fix timeStamp value initializing in SbgEkfNavMessage
- Based on release 3.0.0 of ros1 driver
- update maintainer
- print interface details at startup
- fix configuration files
- Contributors: Michael Zemb, Raphael Siryani
1.0.1 (2020-07-09)
- Update Licenses
- First version
Wiki Tutorials
Package Dependencies
Deps | Name |
---|---|
ament_cmake | |
rosidl_default_generators | |
rosidl_default_runtime | |
geometry_msgs | |
rclcpp | |
sensor_msgs | |
std_msgs | |
std_srvs | |
nav_msgs | |
rtcm_msgs | |
tf2_ros | |
tf2_msgs | |
tf2_geometry_msgs | |
nmea_msgs |
System Dependencies
Dependant Packages
Launch files
Messages
- msg/SbgEkfQuat.msg
- msg/SbgStatusCom.msg
- msg/SbgGpsVel.msg
- msg/SbgMag.msg
- msg/SbgShipMotionStatus.msg
- msg/SbgImuData.msg
- msg/SbgUtcTimeStatus.msg
- msg/SbgShipMotion.msg
- msg/SbgGpsPosStatus.msg
- msg/SbgImuStatus.msg
- msg/SbgStatus.msg
- msg/SbgStatusAiding.msg
- msg/SbgUtcTime.msg
- msg/SbgAirDataStatus.msg
- msg/SbgEkfNav.msg
- msg/SbgEkfEuler.msg
- msg/SbgMagCalib.msg
- msg/SbgGpsRaw.msg
- msg/SbgGpsHdt.msg
- msg/SbgEkfStatus.msg
- msg/SbgStatusGeneral.msg
- msg/SbgGpsPos.msg
- msg/SbgAirData.msg
- msg/SbgEkfRotAccel.msg
- msg/SbgMagStatus.msg
- msg/SbgOdoVel.msg
- msg/SbgImuShort.msg
- msg/SbgGpsVelStatus.msg
- msg/SbgEkfVelBody.msg
- msg/SbgEvent.msg
Services
Plugins
Recent questions tagged sbg_driver at Robotics Stack Exchange
sbg_driver package from sbg_driver reposbg_driver |
|
Package Summary
Tags | No category tags. |
Version | 3.2.0 |
License | MIT |
Build type | CATKIN |
Use | RECOMMENDED |
Repository Summary
Checkout URI | https://github.com/SBG-Systems/sbg_ros_driver.git |
VCS Type | git |
VCS Version | master |
Last Updated | 2024-10-09 |
Dev Status | MAINTAINED |
CI status | Continuous Integration : 0 / 0 |
Released | RELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- SBG Systems
Authors
- SBG Systems
sbg_driver
ROS 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 the following features:
- Configure ELLIPSE products using yaml files (see note below)
- Parse IMU/AHRS/INS/GNSS using the sbgECom protocol
- Publish standard ROS 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
[!NOTE] Only ELLIPSE devices can be configured from the ROS driver. For High Performance INS such as EKINOX, APOGEE and QUANTA, please use the sbgInsRestApi
Installation
Installation from Packages
User can install the sbg_ros_driver through the standard ROS installation system.
- Noetic
sudo apt-get install ros-noetic-sbg-driver
Building from sources
Dependencies
- Robot Operating System (ROS)
- sbgECom C Library (embeds v1.11.920-stable - compatible with ELLIPSE firmware above 1.7)
- Boost C++ Library
Building
- Clone the repository (use a Release version)
cd catkin_ws/src
git clone -b master https://github.com/SBG-Systems/sbg_ros_driver.git
- Install dependencies
cd ..
rosdep install --from-paths src --ignore-src -r -y
- Build using the normal ROS catkin build system
source /opt/ros/${ROS_DISTRO}/setup.bash
catkin_make
Usage
Source the generated setup environment
source devel/setup.bash
To run the default Ros node with the default configuration
roslaunch sbg_driver sbg_device.launch
To run the magnetic calibration node
roslaunch sbg_driver sbg_device_mag_calibration.launch
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 ROS node, so it has to be previously configured (manually or with the ROS node).
It defines a few outputs for the device:-
/sbg/imu_data
,/sbg/ekf_quat
at 25Hz - ROS standard outputs
/imu/data
,/imu/velocity
,/imu/temp
at 25Hz -
/sbg/status
,/sbg/utc_time
and/imu/utc_ref
at 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 ROS node, so it has to be previously configured (manually or with the ROS node).
It defines a few outputs for the device:-
/sbg/imu_data
,/sbg/ekf_quat
at 25Hz - ROS standard outputs
/imu/data
,/imu/velocity
,/imu/temp
at 25Hz -
/sbg/status
,/sbg/utc_time
and/imu/utc_ref
at 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.yaml
configuration. -
sbg_device_mag_calibration_launch.py Launch the sbg_device_mag node to calibrate the magnetometers, and load the
ellipse_E_default.yaml
configuration.
Nodes
sbg_device node
The sbg_device
node handles the communication with the connected device, publishes the SBG output to the ROS environment and subscribes to useful topics such as RTCM data streams.
Published Topics
SBG Systems specific topics
SBG Systems has defined proprietary ROS 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.
-
/sbg/status
sbg_driver/SbgStatusProvides information about the general status (Communication, Aiding, etc..).
-
/sbg/utc_time
sbg_driver/SbgUtcTimeProvides UTC time reference.
-
/sbg/imu_data
sbg_driver/SbgImuDataIMU status, and sensors values.
-
/sbg/ekf_euler
sbg_driver/SbgEkfEulerComputed orientation using Euler angles.
-
/sbg/ekf_quat
sbg_driver/SbgEkfQuatComputed orientation using Quaternion.
-
/sbg/ekf_nav
sbg_driver/SbgEkfNavComputed navigation data.
-
/sbg/mag
sbg_driver/SbgMagCalibrated magnetic field measurement.
-
/sbg/mag_calib
sbg_driver/SbgMagCalibMagnetometer calibration data.
-
/sbg/ship_motion
sbg_driver/SbgShipMotionHeave, surge and sway data.
-
/sbg/gps_vel
sbg_driver/SbgGpsVelGPS velocities from GPS receiver.
-
/sbg/gps_pos
sbg_driver/SbgGpsPosGPS positions from GPS receiver.
-
/sbg/gps_hdt
sbg_driver/SbgGpsHdtGPS true heading from dual antenna system.
-
/sbg/gps_raw
sbg_driver/SbgGpsRawGPS raw data for post processing.
-
/sbg/odo_vel
sbg_driver/SbgOdoVelOdometer velocity.
-
/sbg/event[ABCDE]
sbg_driver/SbgEventEvent on sync in the corresponding pin.
-
/sbg/air_data
sbg_driver/SbgAirDataAir data.
ROS standard topics
[!NOTE] Please update the driver configuration to enable standard ROS messages publication
output.ros_standard
. Also, the driver only publish standard ROS messages if the driver is setup to use ENU frame conventionoutput.use_enu
.
In order to define ROS standard topics, it requires sometimes several SBG messages, to be merged. For each ROS standard, you have to activate the needed SBG outputs.
-
/imu/data
sensor_msgs/ImuIMU data. Requires
/sbg/imu_data
and/sbg/ekf_quat
. -
/imu/temp
sensor_msgs/TemperatureIMU temperature data. Requires
/sbg/imu_data
. -
/imu/velocity
geometry_msgs/TwistStampedIMU velocity data. Requires
/sbg/imu_data
. -
/imu/mag
sensor_msgs/MagneticFieldIMU magnetic field. Requires
/sbg/mag
. -
/imu/pres
sensor_msgs/FluidPressureIMU pressure data. Requires
/sbg/air_data
. -
/imu/pos_ecef
geometry_msgs/PointStampedEarth-Centered Earth-Fixed position. Requires
/sbg/ekf_nav
. -
/imu/utc_ref
sensor_msgs/TimeReferenceUTC time reference. Requires
/sbg/utc_time
. -
/imu/nav_sat_fix
sensor_msgs/NavSatFixNavigation satellite fix for any Global Navigation Satellite System. Requires
/sbg/gps_pos
. -
/imu/odometry
nav_msgs/OdometryUTM projected position relative to the first valid INS position. Requires
/sbg/imu_data
and/sbg/ekv_nav
and either/sbg/ekf_euler
or/sbg/ekf_quat
. Disabled by default, setodometry.enable
in configuration file.
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/nmea
nmea_msgs/SentenceData from
/sbg/gps_pos
serialized into NMEA GGA format. Requires/sbg/gps_pos
.
Namespacentrip_client
and topic_namenmea
can be customized in .yaml config files.
Subscribed Topics
RTCM topics
The sbg_device
node can subscribe to RTCM topics published by third party ROS 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/rtcm
rtcm_msgs/MessageRTCM data from
/ntrip_client/rtcm
will be forwarded to the internal INS GNSS receiver.
Namespacentrip_client
and topic_namertcm
can 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_calibration
std_srvs/TriggerService to start/stop the magnetic calibration.
-
/sbg/mag_calibration_save
std_srvs/TriggerService to save in FLASH memory the latest computed magnetic field calibration.
HowTo
Configure the SBG device
The SBG Ros driver allows the user to configure the device before starting data parsing.
To do so, set the corresponding parameter in the used config file.
# Configuration of the device with ROS.
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.
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 ROS 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 ROS driver:
- For ELLIPSE, simply use the
sbgCenter
and inAssignment panel
,RTCM
should be set toPort A
. - For High Performance INS, either use the configuration web interface or the sbgInsRestApi.
- For ELLIPSE, simply use the
- Install and configure a third party node that broadcast RTCM corrections such as a NTRIP client
- Update the node config
yaml
file to setrtcm.subscribe
andnmea.publish
totrue
- If you use a different node to broadcast RTCM topics, you might have to update the config
yaml
file 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 ROS 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.
1) Make sure you have selected the desired 2D or 3D magnetic field calibration mode (calibration.mode
in the configuration yaml
file).
2) Start a new magnetic calibration session once you are ready to map the magnetic field:
roslaunch sbg_driver sbg_device_mag_calibration.launch
rosservice call /sbg/mag_calibration
success: True
message: “Magnetometer calibration process started.”
3) 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). 4) Once you believe you have covered enough orientations, compute a magnetic field calibration:
rosservice call /sbg/mag_calibration
success: True
message: “Magnetometer calibration is finished. See the output console to get calibration information.”
5) 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)
rosservice call /sbg/mag_calibration_save
success: True
message: “Magnetometer calibration has been uploaded to the device.”
6) 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
ROS 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 ROS 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"
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 ROS 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 ROS 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 |
Navigation Frame:
The navigation frame also referred by ROS as the cartesian representation is defined as follow:
NED Convention | ENU Convention |
---|---|
X North | X East |
Y East | Y North |
Z Down | Z Up |
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.
Changelog for package sbg_driver
3.2.0 (2024-10-09)
- Update README according to the latest changes
- Backported changes from ROS2 driver
- fix #70 build on Windows
- remove unused var
- update doc to build from sources
- Perform proper name resolution to make name remapping more convenient Fixes #75.
- Contributors: Michael Zemb, Richard Braun, Samuel Toledano, cledant
3.1.1 (2021-10-15)
- fix missing dependencies and build status link
- missing dep on nav_msgs, tf2_geometry_msgs, tf2_ros and tf2_msgs
- fix build status link in readme
- update doc with odometry message
- Contributors: Michael Zemb
3.1.0 (2021-10-06)
- Feature #44 - odometry output
- fix #66 - status description for SbgGpsHdt msg
- fix #66 - missing heading and pitch accuracies in sbgGpsHdt msg
- add ellipse D default configuration
- update README
- Contributors: Michael Zemb
3.0.0 (2021-08-31)
- Merge pull request #62 from SBG-Systems/devel Devel
- Merge pull request #61 from SBG-Systems/fix-frame-convention Fix frame convention errors
- Make sure only delta angles/velocities are used
- syntax fixes
- Improved comments & README file
- Fix missing checks on UTC / Unix time computation
- Updated sbgECom messages definitions
- Update README.md and releasePackage.md
- Clean up readme
- Fix position accuracy
- Replace pow by multiplication
- Complete README.md
- Fix bugs in message wrapper and complete message definitions
- Fix Z GPS velocity
- Fix frame convention errors
- Merge pull request #59 from SBG-Systems/fix-frame-id Fix param name
- Fix param name
- Fix inconsistent tab and spaces usages. Now all files are using spaces
- Add wrap 2PI
- Fix bugs
- Fix matrix accuracy
- Fix course
- wrapper: Fix ENU->NED for GPS messages
- warpper: Change createrVector3 names
- wrapper: Fix setter
- wrapper: Fix missing ENU conversion an add comment for cov
- wrapper: Fix regresion
- coding style : Remove tables
- publisher: Configure the wrapper before init the publisher
- main: Fix loopFrequency type
- config: Restore output configuration
- config: Replace enu by use_enu
- enu: Replace enu by use_enu and rename frame convertion function
- frame_id: Change default value
- clean up
- #51 - Correctly fill convariances parameters
- project: Update maintainer
- config: Update parameters
- #45-#50 - Add parameters to set frame ID and ENU convention
- #48 - # 52 Add a parameter to select header stamp source and read ROS time when publishing the message
- #47 Remove node ros::Rate period auto computation and only read it from a node parameter
- clean up: Remove blank spaces
- Merge pull request #35 from ShepelIlya/patch-1 Fixed time_stamp value initializing in SbgEkfNavMessage.
- Added/updated license to MIT
- Updated maintainer
- Fixed timeStamp value initializing in SbgEkfNavMessage.
- Contributors: Michael Zemb, Raphael Siryani, ShepelIlya, bsaussay, rsiryani
2.0.3 (2020-04-01)
- Improve matrix handling
- Fix body velocity computation (Issue #31)
2.0.1 (2020-01-24)
- Improve vector handling
- Fix include file (Issue #26)
2.0.0 (2020-01-06)
- Fix integer type
- Update sbgECom messages (AirData, ImuShort)
- Update sbgECom library to 1.11.920-stable
- Improve numeric type
- Improve configuration applier
- Improve error handling
- Code improvement
- Improve device configuration
- Update changelog
- Update and improve README.md
- Update magnetic services
- Improve message timestamping
- Add some ROS standard sensor messages (Issue #17)
- Comply file structure to ROS best pratices
- Add a processing time to improve message handling
- Add udev rules to documentation (Issue #21)
- Improve magnetometers calibration
- Update maintainer of the package (Issue #20)
- Enable/Disable the configuration of the device (Issue #19)
- Define unified class and launch files for all SBG devices
- Define classes for device configuration
- Merge pull request #18 from SBG-Systems/messagePublisherRework
- Integrate new message publisher to the Ellipse class (Issue #15)
- Define a class to publish messages
- Define class to wrap SBG logs to Ros messages
- Merge pull request #16 from SBG-Systems/v4.3
- [src] Update SDK version + add LogE support
- Merge pull request #13 from nicolaje/remove-non-ascii-char
- [conf] Removed non-ASCII characters, (Issue #8)
- [msg] Remove non ascii characters
1.1.7 (2018-07-19)
- [src] Change SbgEkfEuler comments
- [src] Move .h to include folder + test new method for time saving in calib
1.1.6 (2018-03-18)
- [config, src] Update default port for gps aiding (Ellipse-E) + add save & reboot for mag calibration
- [build] Add include for debian jessie arm64 build issue
1.1.5 (2018-03-12 23:49)
- [src] Update mag calibration
1.1.4 (2018-03-12 23:10)
- [catkin] Update install launch & config
- [src] Update library + Correction bugs
1.1.3 (2018-03-12 11:46)
- Update dependencies to std_srvs
1.1.2 (2018-03-12 09:54)
- [ChangeLog] Remove
- [ChangeLog] Update
- [Changelog] Test
- [test] Changelog
- [Changelog] Update
- [CMake] Correction of message dependency
1.1.1 (2018-03-11)
- [xml] Update version number
- [src] Correction of small bugs + add publisher only on activated log
- [merge] Finalize merge from devel branch (master divergence issue)
- [lib] Update the library sbgECom version after merging from devel
- [Merge]
- Merge branch 'master' of https://github.com/ENSTABretagneRobotics/sbg_ros_driver
- [src] Update doc
- [src] Update magnetic calibration node
- Revert "1.0.7" This reverts commit 8f57f9e578937ac23383e39ebf616d1039384b09.
- Update README
- Merge pull request #2 from rpng/master Upgrade sbg_ros_driver
- Moved the logging function into the class
- Added - Start of heading code
- Refactor and added new publishers
- Increased rates
- refactoring use a class for callbacks changed callbacks around a bit, now shows raw data rather than ekf logs
- use gps log message for NavSatFix message
- add extra debug messages
- use private namespace
- modified launch file moved to launch folder and added optional arguments
- updated sbgECom library
1.1.0 (2018-03-10)
- [src] Update Events
- [src] Add params
- [src] Update (add configuration of the ellipse)
- [src] Update messages
- [src] Start creating sbg messages
1.0.7 (2017-04-01)
- [src][minor] Correct launch file
1.0.6 (2017-03-31)
- CHANGELOG
- [src] Add launch example
- [src] Change imu data & add gyroscopes
1.0.5 (2016-11-17 00:04)
1.0.4 (2016-11-17 00:02)
1.0.3 (2016-11-16 23:59)
- [src][minor] Correction of Project name in CmakeList
1.0.2 (2016-11-16 22:58)
- [doc] minor
- [doc] Update Package
1.0.1 (2016-11-16 22:30)
- [doc] Update package version to 1.0.0
- [doc] Add Changelog
- [src] Update of deprecated function
- [src] Update (correcting cmake sub project)
- [src] Correct cmake subdirectory issue
- Initial commit
Wiki Tutorials
Package Dependencies
Deps | Name |
---|---|
roscpp | |
sensor_msgs | |
std_msgs | |
std_srvs | |
geometry_msgs | |
message_generation | |
nav_msgs | |
tf2_ros | |
tf2_msgs | |
tf2_geometry_msgs | |
rtcm_msgs | |
nmea_msgs | |
catkin | |
message_runtime |
System Dependencies
Dependant Packages
Launch files
Messages
- msg/SbgEkfQuat.msg
- msg/SbgStatusCom.msg
- msg/SbgGpsVel.msg
- msg/SbgMag.msg
- msg/SbgShipMotionStatus.msg
- msg/SbgImuData.msg
- msg/SbgUtcTimeStatus.msg
- msg/SbgShipMotion.msg
- msg/SbgGpsPosStatus.msg
- msg/SbgImuStatus.msg
- msg/SbgStatus.msg
- msg/SbgStatusAiding.msg
- msg/SbgUtcTime.msg
- msg/SbgAirDataStatus.msg
- msg/SbgEkfNav.msg
- msg/SbgEkfEuler.msg
- msg/SbgMagCalib.msg
- msg/SbgGpsRaw.msg
- msg/SbgGpsHdt.msg
- msg/SbgEkfStatus.msg
- msg/SbgStatusGeneral.msg
- msg/SbgGpsPos.msg
- msg/SbgAirData.msg
- msg/SbgMagStatus.msg
- msg/SbgOdoVel.msg
- msg/SbgImuShort.msg
- msg/SbgGpsVelStatus.msg
- msg/SbgEvent.msg
Services
Plugins
Recent questions tagged sbg_driver at Robotics Stack Exchange
sbg_driver package from sbg_driver reposbg_driver |
|
Package Summary
Tags | No category tags. |
Version | 3.2.0 |
License | MIT |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Checkout URI | https://github.com/SBG-Systems/sbg_ros2.git |
VCS Type | git |
VCS Version | master |
Last Updated | 2024-10-17 |
Dev Status | DEVELOPED |
CI status | No Continuous Integration |
Released | RELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- SBG Systems
Authors
- SBG Systems
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 the following features:
- Configure ELLIPSE products using yaml files (see note below)
- Parse IMU/AHRS/INS/GNSS using the sbgECom protocol
- Publish standard ROS 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
[!NOTE] Only ELLIPSE devices can be configured from the ROS driver. For High Performance INS such as EKINOX, APOGEE and QUANTA, please use the sbgInsRestApi
Installation
Installation from Packages
User can install the sbg_ros2_driver through the standard ROS installation system.
- Galactic
sudo apt-get install ros-galactic-sbg-driver
- Foxy
sudo apt-get install ros-foxy-sbg-driver
Building from sources
Dependencies
- Robot Operating System (ROS)
- 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 ROS 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
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 ROS node, so it has to be previously configured (manually or with the ROS node).
It defines a few outputs for the device:-
/sbg/imu_data
,/sbg/ekf_quat
at 25Hz - ROS standard outputs
/imu/data
,/imu/velocity
,/imu/temp
at 25Hz -
/sbg/status
,/sbg/utc_time
and/imu/utc_ref
at 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 ROS node, so it has to be previously configured (manually or with the ROS node).
It defines a few outputs for the device:-
/sbg/imu_data
,/sbg/ekf_quat
at 25Hz - ROS standard outputs
/imu/data
,/imu/velocity
,/imu/temp
at 25Hz -
/sbg/status
,/sbg/utc_time
and/imu/utc_ref
at 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.yaml
configuration. -
sbg_device_mag_calibration_launch.py Launch the sbg_device_mag node to calibrate the magnetometers, and load the
ellipse_E_default.yaml
configuration.
Nodes
sbg_device node
The sbg_device
node handles the communication with the connected device, publishes the SBG output to the Ros environment and subscribes to useful topics such as RTCM data streams.
Published Topics
SBG Systems specific topics
SBG Systems has defined proprietary ROS 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.
-
/sbg/status
sbg_driver/SbgStatusProvides information about the general status (Communication, Aiding, etc..).
-
/sbg/utc_time
sbg_driver/SbgUtcTimeProvides UTC time reference.
-
/sbg/imu_data
sbg_driver/SbgImuDataIMU status, and sensors values.
-
/sbg/ekf_euler
sbg_driver/SbgEkfEulerComputed orientation using Euler angles.
-
/sbg/ekf_quat
sbg_driver/SbgEkfQuatComputed orientation using Quaternion.
-
/sbg/ekf_nav
sbg_driver/SbgEkfNavComputed navigation data.
-
/sbg/ekf_vel_body
sbg_driver/SbgEkfVelBodyComputed velocity expressed in the INS body/vehicle frame.
-
/sbg/ekf_rot_accel_body
sbg_driver/SbgEkfRotAccelComputed rotations rate and accelerations in the INS body/vehicle frame.
-
/sbg/ekf_rot_accel_ned
sbg_driver/SbgEkfRotAccelComputed rotations rate and accelerations in North, East, Down (NED) navigation frame.
-
/sbg/mag
sbg_driver/SbgMagCalibrated magnetic field measurement.
-
/sbg/mag_calib
sbg_driver/SbgMagCalibMagnetometer calibration data.
-
/sbg/ship_motion
sbg_driver/SbgShipMotionHeave, surge and sway data.
-
/sbg/gps_vel
sbg_driver/SbgGpsVelGPS velocities from GPS receiver.
-
/sbg/gps_pos
sbg_driver/SbgGpsPosGPS positions from GPS receiver.
-
/sbg/gps_hdt
sbg_driver/SbgGpsHdtGPS true heading from dual antenna system.
-
/sbg/gps_raw
sbg_driver/SbgGpsRawGPS raw data for post processing.
-
/sbg/odo_vel
sbg_driver/SbgOdoVelOdometer velocity.
-
/sbg/event[ABCDE]
sbg_driver/SbgEventEvent on sync in the corresponding pin.
-
/sbg/pressure
sbg_driver/SbgPressurePressure data.
ROS standard topics
In order to define ROS standard topics, it requires sometimes several SBG messages, to be merged. For each ROS standard, you have to activate the needed SBG outputs.
-
/imu/data
sensor_msgs/ImuIMU data. Requires
/sbg/imu_data
and/sbg/ekf_quat
. -
/imu/temp
sensor_msgs/TemperatureIMU temperature data. Requires
/sbg/imu_data
. -
/imu/velocity
geometry_msgs/TwistStampedIMU velocity data. Requires
/sbg/imu_data
. -
/imu/mag
sensor_msgs/MagneticFieldIMU magnetic field. Requires
/sbg/mag
. -
/imu/pres
sensor_msgs/FluidPressureIMU pressure data. Requires
/sbg/pressure
. -
/imu/pos_ecef
geometry_msgs/PointStampedEarth-Centered Earth-Fixed position. Requires
/sbg/ekf_nav
. -
/imu/utc_ref
sensor_msgs/TimeReferenceUTC time reference. Requires
/sbg/utc_time
. -
/imu/nav_sat_fix
sensor_msgs/NavSatFixNavigation satellite fix for any Global Navigation Satellite System. Requires
/sbg/gps_pos
. -
/imu/odometry
nav_msgs/OdometryUTM projected position relative to the first valid INS position. Requires
/sbg/imu_data
and/sbg/ekv_nav
and either/sbg/ekf_euler
or/sbg/ekf_quat
. Disabled by default, setodometry.enable
in configuration file.
[!NOTE] Please update the driver configuration to enable standard ROS messages publication. Also, the driver only publish standard ROS 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/nmea
nmea_msgs/SentenceData from
/sbg/gps_pos
serialized into NMEA GGA format. Requires/sbg/gps_pos
.
Namespacentrip_client
and topic_namenmea
can 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/rtcm
rtcm_msgs/MessageRTCM data from
/ntrip_client/rtcm
will be forwarded to the internal INS GNSS receiver.
Namespacentrip_client
and topic_namertcm
can 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_calibration
std_srvs/TriggerService to start/stop the magnetic calibration.
-
/sbg/mag_calibration_save
std_srvs/TriggerService to save in FLASH memory the latest computed magnetic field calibration.
HowTo
Configure the SBG device
The SBG Ros driver allows the user to configure the device before starting data parsing.
To do so, set the corresponding parameter in the used config file.
# Configuration of the device with ROS.
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.
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 ROS 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 ROS driver:
- For ELLIPSE, simply use the
sbgCenter
and inAssignment panel
,RTCM
should be set toPort A
. - For High Performance INS, either use the configuration web interface or the sbgInsRestApi.
- For ELLIPSE, simply use the
- Install and configure a third party node that broadcast RTCM corrections such as a NTRIP client
- Update the node config
yaml
file to setrtcm.subscribe
andnmea.publish
totrue
- If you use a different node to broadcast RTCM topics, you might have to update the config
yaml
file 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 ROS 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.
1) Make sure you have selected the desired 2D or 3D magnetic field calibration mode (calibration.mode
in the configuration yaml
file).
2) 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.’)
3) 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). 4) 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.’)
5) 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.’)
6) 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
ROS 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 ROS 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"
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 ROS 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 ROS 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 |
Navigation Frame:
The navigation frame also referred by ROS as the cartesian representation is defined as follow:
NED Convention | ENU Convention |
---|---|
X North | X East |
Y East | Y North |
Z Down | Z Up |
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.
Changelog for package sbg_driver
3.2.0 (2024-10-17)
- Update README with ROS2 commands to launch magnetic calibration
- Fix segfault when running magnetic calibration
- Removed unused flags from SbgEkfStatus message
- Added new flags to SbgShipMotionStatus message
- Improved SbgStatusAiding message with new flags
- Improved SbgPosStatus message with new flags
- Improved SbgEkfStatus message with new flags
- Improved SbgStatusGeneral message with datalogger and cpu flags
- Updated documentation for sbgGpsPos message
- Updated documentation for sbgGpsHdt message
- Improved SbgUtcTime message with internal clock quality indicators
- Improved SbgStatusCom message with ethernet tx and rx status
- Improved SbgGpsHdt message with number of SV tracked and used
- Improved SbgGpsPos message with numSvTracked
- Improved SbgGpsPosStatus message with spoofing, jamming and OSNMA status
- Updated config files with new messages
- Removed obsolete documentation
- Updated published topic list
- Added missing topic names
- Updated dependencies requirement
- Added settings log_ekf_rot_accel_body / log_ekf_rot_accel_ned / log_ekf_vel_body
- Fixed functions description
- Added SbgEkfRotAccel body and NED messages
- Added SbgEkfVelBody message
- Fixing compiling issues
- Updated sbgECom lib with version 4.0-1987-stable
- Fixed typos about lever arm
- Fixed config applier for IMU Alignment / Aiding / Odometer lever arms
- Remove boost dependency (cherry picked from commit ab54c33f1e442c3737dd8e1c09a8b6f36c2c1afa)
- Cleanup
- Moved LLAtoECEF into a helper
- Variable naming
- WIP code cleanup
- Class documentation
- Code indentation
- Utm as class
- Indentation fix
- Updated sbg_utm documentation and function prototype
- Added documentation on Utm structure
- Added documentation on Position class
- Added Position class
- Factory for UTM data
- Fixed space / tabluations issues
- Code indentation
- SbgUtm documentation
- Using fma for computation
- Added constexpr to some variables
- Using pow instead of multiply
- Reworked createRosPointStampedMessage computations
- Removed sendTransform in fillTransform method
- Moved functions into helper namespace
- Moved UTM initialization into its own class
- Removed catkin reference in CMakeLists.txt
- Updated naming convention
- Improved ENU/NED documentation
- Disabling ROS standard message when in NED frame convention
- Reverted NED to ENU quaternion conversion
- Quaternion: cleaner version for NED to ENU conversion
- Reworked odometry message
- Quaternion: NED to ENU conversion rework
- Updated readme about ENU frame convention
- Reworked angle wrapping functions
- Added range for Euler angle measurement.
- More explicit naming for quaternions
- Reverted NED to ENU array conversion
- Documentation update
- odom->base_link is now correct in NED mode
- Renamed function.
- Fixed variable inversion.
- odom->base_link is now correct in NED mode
- Refactored NED to ENU array conversion
- Updated ROS messages documentation
- Fixed Euler / Quaternion orientation in ENU mode
- Fixed nmea output condition
- Compilation fixes
- NTRIP: GGA generation Work In Progress with the following fixex:
- GPS to UTC time correctly apply leap second offset
- GGA only sent if a valid position is available
- GGA is sent at 1 Hz only
- Minor improvements Code is not yet tested nor build
- Compilation fix
- Improved GGA generation and code cleanup
- Improved RTCM and NMEA parameters naming
- Code cleanup - removed (void) as it is not recommended in C++
- Reworked and improved main project README and small fixed in yaml examples
- Added documentation about RTCM messages and device configuration.
- Removed MessageSubscriber class
- Switched dependency from mavros_msgs to rtcm_msgs
- Updated documentation
- Removed SbgInterface as class member
- Removed threaded subscription.
- Namespace related coding style fix
- Fixes in GGA serialization
- Realigned members.
- Code documentation
- Improved NMEA GGA message
- Added rtcm / nmea parameters in config files
- Fixed deprecated header warning
- Added publisher for nmea msg
- Added subscription to RTCM msg
- remove build status
- fix build on Windows
- time_reference parameter fix
- Fix deprecated use of rosidl_target_interfaces The use of rosidl_target_interfaces is deprecated (see [Humble release notes](http://docs.ros.org.ros.informatik.uni-freiburg.de/en/humble/Releases/Release-Humble-Hawksbill.html#deprecation-of-rosidl-target-interfaces). Here that actually causes an issue with CMake not setting the right include directory paths, breaking [colcon build]{.title-ref} on humble. This applies the documented update, making the driver build under Humble
- Contributors: Michael Zemb, Raphael Siryani, Samuel Toledano, SanderVanDijk-StreetDrone, Timon Mentink, VladimirL, cledant, rsiryani
3.1.0 (2021-10-18)
- Add imu/odometry publisher
- Fix dependencies
- Fix wrong SbgGpsHdt description
- Update doc
- Add missing MIT licences
- Based on release 3.1 of ros1 driver
- Add ENU/NED option, rework frame IDs, time stamps and driver
frequency.
- Add parameters to set frame ID and ENU convention
- Add a parameter to select header stamp source and read ROS time when publishing the message
- Remove node ros::Rate period auto computation and only read it from a node parameter
- Update documentation and messages definitions
- Fix timeStamp value initializing in SbgEkfNavMessage
- Based on release 3.0.0 of ros1 driver
- update maintainer
- print interface details at startup
- fix configuration files
- Contributors: Michael Zemb, Raphael Siryani
1.0.1 (2020-07-09)
- Update Licenses
- First version
Wiki Tutorials
Package Dependencies
Deps | Name |
---|---|
ament_cmake | |
rosidl_default_generators | |
rosidl_default_runtime | |
geometry_msgs | |
rclcpp | |
sensor_msgs | |
std_msgs | |
std_srvs | |
nav_msgs | |
rtcm_msgs | |
tf2_ros | |
tf2_msgs | |
tf2_geometry_msgs | |
nmea_msgs |
System Dependencies
Dependant Packages
Launch files
Messages
- msg/SbgEkfQuat.msg
- msg/SbgStatusCom.msg
- msg/SbgGpsVel.msg
- msg/SbgMag.msg
- msg/SbgShipMotionStatus.msg
- msg/SbgImuData.msg
- msg/SbgUtcTimeStatus.msg
- msg/SbgShipMotion.msg
- msg/SbgGpsPosStatus.msg
- msg/SbgImuStatus.msg
- msg/SbgStatus.msg
- msg/SbgStatusAiding.msg
- msg/SbgUtcTime.msg
- msg/SbgAirDataStatus.msg
- msg/SbgEkfNav.msg
- msg/SbgEkfEuler.msg
- msg/SbgMagCalib.msg
- msg/SbgGpsRaw.msg
- msg/SbgGpsHdt.msg
- msg/SbgEkfStatus.msg
- msg/SbgStatusGeneral.msg
- msg/SbgGpsPos.msg
- msg/SbgAirData.msg
- msg/SbgEkfRotAccel.msg
- msg/SbgMagStatus.msg
- msg/SbgOdoVel.msg
- msg/SbgImuShort.msg
- msg/SbgGpsVelStatus.msg
- msg/SbgEkfVelBody.msg
- msg/SbgEvent.msg
Services
Plugins
Recent questions tagged sbg_driver at Robotics Stack Exchange
sbg_driver package from sbg_driver reposbg_driver |
|
Package Summary
Tags | No category tags. |
Version | 3.2.0 |
License | MIT |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Checkout URI | https://github.com/SBG-Systems/sbg_ros2.git |
VCS Type | git |
VCS Version | master |
Last Updated | 2024-10-17 |
Dev Status | DEVELOPED |
CI status | No Continuous Integration |
Released | RELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- SBG Systems
Authors
- SBG Systems
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 the following features:
- Configure ELLIPSE products using yaml files (see note below)
- Parse IMU/AHRS/INS/GNSS using the sbgECom protocol
- Publish standard ROS 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
[!NOTE] Only ELLIPSE devices can be configured from the ROS driver. For High Performance INS such as EKINOX, APOGEE and QUANTA, please use the sbgInsRestApi
Installation
Installation from Packages
User can install the sbg_ros2_driver through the standard ROS installation system.
- Galactic
sudo apt-get install ros-galactic-sbg-driver
- Foxy
sudo apt-get install ros-foxy-sbg-driver
Building from sources
Dependencies
- Robot Operating System (ROS)
- 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 ROS 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
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 ROS node, so it has to be previously configured (manually or with the ROS node).
It defines a few outputs for the device:-
/sbg/imu_data
,/sbg/ekf_quat
at 25Hz - ROS standard outputs
/imu/data
,/imu/velocity
,/imu/temp
at 25Hz -
/sbg/status
,/sbg/utc_time
and/imu/utc_ref
at 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 ROS node, so it has to be previously configured (manually or with the ROS node).
It defines a few outputs for the device:-
/sbg/imu_data
,/sbg/ekf_quat
at 25Hz - ROS standard outputs
/imu/data
,/imu/velocity
,/imu/temp
at 25Hz -
/sbg/status
,/sbg/utc_time
and/imu/utc_ref
at 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.yaml
configuration. -
sbg_device_mag_calibration_launch.py Launch the sbg_device_mag node to calibrate the magnetometers, and load the
ellipse_E_default.yaml
configuration.
Nodes
sbg_device node
The sbg_device
node handles the communication with the connected device, publishes the SBG output to the Ros environment and subscribes to useful topics such as RTCM data streams.
Published Topics
SBG Systems specific topics
SBG Systems has defined proprietary ROS 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.
-
/sbg/status
sbg_driver/SbgStatusProvides information about the general status (Communication, Aiding, etc..).
-
/sbg/utc_time
sbg_driver/SbgUtcTimeProvides UTC time reference.
-
/sbg/imu_data
sbg_driver/SbgImuDataIMU status, and sensors values.
-
/sbg/ekf_euler
sbg_driver/SbgEkfEulerComputed orientation using Euler angles.
-
/sbg/ekf_quat
sbg_driver/SbgEkfQuatComputed orientation using Quaternion.
-
/sbg/ekf_nav
sbg_driver/SbgEkfNavComputed navigation data.
-
/sbg/ekf_vel_body
sbg_driver/SbgEkfVelBodyComputed velocity expressed in the INS body/vehicle frame.
-
/sbg/ekf_rot_accel_body
sbg_driver/SbgEkfRotAccelComputed rotations rate and accelerations in the INS body/vehicle frame.
-
/sbg/ekf_rot_accel_ned
sbg_driver/SbgEkfRotAccelComputed rotations rate and accelerations in North, East, Down (NED) navigation frame.
-
/sbg/mag
sbg_driver/SbgMagCalibrated magnetic field measurement.
-
/sbg/mag_calib
sbg_driver/SbgMagCalibMagnetometer calibration data.
-
/sbg/ship_motion
sbg_driver/SbgShipMotionHeave, surge and sway data.
-
/sbg/gps_vel
sbg_driver/SbgGpsVelGPS velocities from GPS receiver.
-
/sbg/gps_pos
sbg_driver/SbgGpsPosGPS positions from GPS receiver.
-
/sbg/gps_hdt
sbg_driver/SbgGpsHdtGPS true heading from dual antenna system.
-
/sbg/gps_raw
sbg_driver/SbgGpsRawGPS raw data for post processing.
-
/sbg/odo_vel
sbg_driver/SbgOdoVelOdometer velocity.
-
/sbg/event[ABCDE]
sbg_driver/SbgEventEvent on sync in the corresponding pin.
-
/sbg/pressure
sbg_driver/SbgPressurePressure data.
ROS standard topics
In order to define ROS standard topics, it requires sometimes several SBG messages, to be merged. For each ROS standard, you have to activate the needed SBG outputs.
-
/imu/data
sensor_msgs/ImuIMU data. Requires
/sbg/imu_data
and/sbg/ekf_quat
. -
/imu/temp
sensor_msgs/TemperatureIMU temperature data. Requires
/sbg/imu_data
. -
/imu/velocity
geometry_msgs/TwistStampedIMU velocity data. Requires
/sbg/imu_data
. -
/imu/mag
sensor_msgs/MagneticFieldIMU magnetic field. Requires
/sbg/mag
. -
/imu/pres
sensor_msgs/FluidPressureIMU pressure data. Requires
/sbg/pressure
. -
/imu/pos_ecef
geometry_msgs/PointStampedEarth-Centered Earth-Fixed position. Requires
/sbg/ekf_nav
. -
/imu/utc_ref
sensor_msgs/TimeReferenceUTC time reference. Requires
/sbg/utc_time
. -
/imu/nav_sat_fix
sensor_msgs/NavSatFixNavigation satellite fix for any Global Navigation Satellite System. Requires
/sbg/gps_pos
. -
/imu/odometry
nav_msgs/OdometryUTM projected position relative to the first valid INS position. Requires
/sbg/imu_data
and/sbg/ekv_nav
and either/sbg/ekf_euler
or/sbg/ekf_quat
. Disabled by default, setodometry.enable
in configuration file.
[!NOTE] Please update the driver configuration to enable standard ROS messages publication. Also, the driver only publish standard ROS 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/nmea
nmea_msgs/SentenceData from
/sbg/gps_pos
serialized into NMEA GGA format. Requires/sbg/gps_pos
.
Namespacentrip_client
and topic_namenmea
can 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/rtcm
rtcm_msgs/MessageRTCM data from
/ntrip_client/rtcm
will be forwarded to the internal INS GNSS receiver.
Namespacentrip_client
and topic_namertcm
can 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_calibration
std_srvs/TriggerService to start/stop the magnetic calibration.
-
/sbg/mag_calibration_save
std_srvs/TriggerService to save in FLASH memory the latest computed magnetic field calibration.
HowTo
Configure the SBG device
The SBG Ros driver allows the user to configure the device before starting data parsing.
To do so, set the corresponding parameter in the used config file.
# Configuration of the device with ROS.
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.
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 ROS 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 ROS driver:
- For ELLIPSE, simply use the
sbgCenter
and inAssignment panel
,RTCM
should be set toPort A
. - For High Performance INS, either use the configuration web interface or the sbgInsRestApi.
- For ELLIPSE, simply use the
- Install and configure a third party node that broadcast RTCM corrections such as a NTRIP client
- Update the node config
yaml
file to setrtcm.subscribe
andnmea.publish
totrue
- If you use a different node to broadcast RTCM topics, you might have to update the config
yaml
file 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 ROS 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.
1) Make sure you have selected the desired 2D or 3D magnetic field calibration mode (calibration.mode
in the configuration yaml
file).
2) 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.’)
3) 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). 4) 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.’)
5) 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.’)
6) 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
ROS 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 ROS 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"
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 ROS 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 ROS 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 |
Navigation Frame:
The navigation frame also referred by ROS as the cartesian representation is defined as follow:
NED Convention | ENU Convention |
---|---|
X North | X East |
Y East | Y North |
Z Down | Z Up |
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.
Changelog for package sbg_driver
3.2.0 (2024-10-17)
- Update README with ROS2 commands to launch magnetic calibration
- Fix segfault when running magnetic calibration
- Removed unused flags from SbgEkfStatus message
- Added new flags to SbgShipMotionStatus message
- Improved SbgStatusAiding message with new flags
- Improved SbgPosStatus message with new flags
- Improved SbgEkfStatus message with new flags
- Improved SbgStatusGeneral message with datalogger and cpu flags
- Updated documentation for sbgGpsPos message
- Updated documentation for sbgGpsHdt message
- Improved SbgUtcTime message with internal clock quality indicators
- Improved SbgStatusCom message with ethernet tx and rx status
- Improved SbgGpsHdt message with number of SV tracked and used
- Improved SbgGpsPos message with numSvTracked
- Improved SbgGpsPosStatus message with spoofing, jamming and OSNMA status
- Updated config files with new messages
- Removed obsolete documentation
- Updated published topic list
- Added missing topic names
- Updated dependencies requirement
- Added settings log_ekf_rot_accel_body / log_ekf_rot_accel_ned / log_ekf_vel_body
- Fixed functions description
- Added SbgEkfRotAccel body and NED messages
- Added SbgEkfVelBody message
- Fixing compiling issues
- Updated sbgECom lib with version 4.0-1987-stable
- Fixed typos about lever arm
- Fixed config applier for IMU Alignment / Aiding / Odometer lever arms
- Remove boost dependency (cherry picked from commit ab54c33f1e442c3737dd8e1c09a8b6f36c2c1afa)
- Cleanup
- Moved LLAtoECEF into a helper
- Variable naming
- WIP code cleanup
- Class documentation
- Code indentation
- Utm as class
- Indentation fix
- Updated sbg_utm documentation and function prototype
- Added documentation on Utm structure
- Added documentation on Position class
- Added Position class
- Factory for UTM data
- Fixed space / tabluations issues
- Code indentation
- SbgUtm documentation
- Using fma for computation
- Added constexpr to some variables
- Using pow instead of multiply
- Reworked createRosPointStampedMessage computations
- Removed sendTransform in fillTransform method
- Moved functions into helper namespace
- Moved UTM initialization into its own class
- Removed catkin reference in CMakeLists.txt
- Updated naming convention
- Improved ENU/NED documentation
- Disabling ROS standard message when in NED frame convention
- Reverted NED to ENU quaternion conversion
- Quaternion: cleaner version for NED to ENU conversion
- Reworked odometry message
- Quaternion: NED to ENU conversion rework
- Updated readme about ENU frame convention
- Reworked angle wrapping functions
- Added range for Euler angle measurement.
- More explicit naming for quaternions
- Reverted NED to ENU array conversion
- Documentation update
- odom->base_link is now correct in NED mode
- Renamed function.
- Fixed variable inversion.
- odom->base_link is now correct in NED mode
- Refactored NED to ENU array conversion
- Updated ROS messages documentation
- Fixed Euler / Quaternion orientation in ENU mode
- Fixed nmea output condition
- Compilation fixes
- NTRIP: GGA generation Work In Progress with the following fixex:
- GPS to UTC time correctly apply leap second offset
- GGA only sent if a valid position is available
- GGA is sent at 1 Hz only
- Minor improvements Code is not yet tested nor build
- Compilation fix
- Improved GGA generation and code cleanup
- Improved RTCM and NMEA parameters naming
- Code cleanup - removed (void) as it is not recommended in C++
- Reworked and improved main project README and small fixed in yaml examples
- Added documentation about RTCM messages and device configuration.
- Removed MessageSubscriber class
- Switched dependency from mavros_msgs to rtcm_msgs
- Updated documentation
- Removed SbgInterface as class member
- Removed threaded subscription.
- Namespace related coding style fix
- Fixes in GGA serialization
- Realigned members.
- Code documentation
- Improved NMEA GGA message
- Added rtcm / nmea parameters in config files
- Fixed deprecated header warning
- Added publisher for nmea msg
- Added subscription to RTCM msg
- remove build status
- fix build on Windows
- time_reference parameter fix
- Fix deprecated use of rosidl_target_interfaces The use of rosidl_target_interfaces is deprecated (see [Humble release notes](http://docs.ros.org.ros.informatik.uni-freiburg.de/en/humble/Releases/Release-Humble-Hawksbill.html#deprecation-of-rosidl-target-interfaces). Here that actually causes an issue with CMake not setting the right include directory paths, breaking [colcon build]{.title-ref} on humble. This applies the documented update, making the driver build under Humble
- Contributors: Michael Zemb, Raphael Siryani, Samuel Toledano, SanderVanDijk-StreetDrone, Timon Mentink, VladimirL, cledant, rsiryani
3.1.0 (2021-10-18)
- Add imu/odometry publisher
- Fix dependencies
- Fix wrong SbgGpsHdt description
- Update doc
- Add missing MIT licences
- Based on release 3.1 of ros1 driver
- Add ENU/NED option, rework frame IDs, time stamps and driver
frequency.
- Add parameters to set frame ID and ENU convention
- Add a parameter to select header stamp source and read ROS time when publishing the message
- Remove node ros::Rate period auto computation and only read it from a node parameter
- Update documentation and messages definitions
- Fix timeStamp value initializing in SbgEkfNavMessage
- Based on release 3.0.0 of ros1 driver
- update maintainer
- print interface details at startup
- fix configuration files
- Contributors: Michael Zemb, Raphael Siryani
1.0.1 (2020-07-09)
- Update Licenses
- First version
Wiki Tutorials
Package Dependencies
Deps | Name |
---|---|
ament_cmake | |
rosidl_default_generators | |
rosidl_default_runtime | |
geometry_msgs | |
rclcpp | |
sensor_msgs | |
std_msgs | |
std_srvs | |
nav_msgs | |
rtcm_msgs | |
tf2_ros | |
tf2_msgs | |
tf2_geometry_msgs | |
nmea_msgs |
System Dependencies
Dependant Packages
Launch files
Messages
- msg/SbgEkfQuat.msg
- msg/SbgStatusCom.msg
- msg/SbgGpsVel.msg
- msg/SbgMag.msg
- msg/SbgShipMotionStatus.msg
- msg/SbgImuData.msg
- msg/SbgUtcTimeStatus.msg
- msg/SbgShipMotion.msg
- msg/SbgGpsPosStatus.msg
- msg/SbgImuStatus.msg
- msg/SbgStatus.msg
- msg/SbgStatusAiding.msg
- msg/SbgUtcTime.msg
- msg/SbgAirDataStatus.msg
- msg/SbgEkfNav.msg
- msg/SbgEkfEuler.msg
- msg/SbgMagCalib.msg
- msg/SbgGpsRaw.msg
- msg/SbgGpsHdt.msg
- msg/SbgEkfStatus.msg
- msg/SbgStatusGeneral.msg
- msg/SbgGpsPos.msg
- msg/SbgAirData.msg
- msg/SbgEkfRotAccel.msg
- msg/SbgMagStatus.msg
- msg/SbgOdoVel.msg
- msg/SbgImuShort.msg
- msg/SbgGpsVelStatus.msg
- msg/SbgEkfVelBody.msg
- msg/SbgEvent.msg
Services
Plugins
Recent questions tagged sbg_driver at Robotics Stack Exchange
sbg_driver package from sbg_driver reposbg_driver |
|
Package Summary
Tags | No category tags. |
Version | 3.2.0 |
License | MIT |
Build type | CATKIN |
Use | RECOMMENDED |
Repository Summary
Checkout URI | https://github.com/SBG-Systems/sbg_ros_driver.git |
VCS Type | git |
VCS Version | master |
Last Updated | 2024-10-09 |
Dev Status | MAINTAINED |
CI status | Continuous Integration |
Released | RELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- SBG Systems
Authors
- SBG Systems
sbg_driver
ROS 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 the following features:
- Configure ELLIPSE products using yaml files (see note below)
- Parse IMU/AHRS/INS/GNSS using the sbgECom protocol
- Publish standard ROS 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
[!NOTE] Only ELLIPSE devices can be configured from the ROS driver. For High Performance INS such as EKINOX, APOGEE and QUANTA, please use the sbgInsRestApi
Installation
Installation from Packages
User can install the sbg_ros_driver through the standard ROS installation system.
- Noetic
sudo apt-get install ros-noetic-sbg-driver
Building from sources
Dependencies
- Robot Operating System (ROS)
- sbgECom C Library (embeds v1.11.920-stable - compatible with ELLIPSE firmware above 1.7)
- Boost C++ Library
Building
- Clone the repository (use a Release version)
cd catkin_ws/src
git clone -b master https://github.com/SBG-Systems/sbg_ros_driver.git
- Install dependencies
cd ..
rosdep install --from-paths src --ignore-src -r -y
- Build using the normal ROS catkin build system
source /opt/ros/${ROS_DISTRO}/setup.bash
catkin_make
Usage
Source the generated setup environment
source devel/setup.bash
To run the default Ros node with the default configuration
roslaunch sbg_driver sbg_device.launch
To run the magnetic calibration node
roslaunch sbg_driver sbg_device_mag_calibration.launch
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 ROS node, so it has to be previously configured (manually or with the ROS node).
It defines a few outputs for the device:-
/sbg/imu_data
,/sbg/ekf_quat
at 25Hz - ROS standard outputs
/imu/data
,/imu/velocity
,/imu/temp
at 25Hz -
/sbg/status
,/sbg/utc_time
and/imu/utc_ref
at 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 ROS node, so it has to be previously configured (manually or with the ROS node).
It defines a few outputs for the device:-
/sbg/imu_data
,/sbg/ekf_quat
at 25Hz - ROS standard outputs
/imu/data
,/imu/velocity
,/imu/temp
at 25Hz -
/sbg/status
,/sbg/utc_time
and/imu/utc_ref
at 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.yaml
configuration. -
sbg_device_mag_calibration_launch.py Launch the sbg_device_mag node to calibrate the magnetometers, and load the
ellipse_E_default.yaml
configuration.
Nodes
sbg_device node
The sbg_device
node handles the communication with the connected device, publishes the SBG output to the ROS environment and subscribes to useful topics such as RTCM data streams.
Published Topics
SBG Systems specific topics
SBG Systems has defined proprietary ROS 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.
-
/sbg/status
sbg_driver/SbgStatusProvides information about the general status (Communication, Aiding, etc..).
-
/sbg/utc_time
sbg_driver/SbgUtcTimeProvides UTC time reference.
-
/sbg/imu_data
sbg_driver/SbgImuDataIMU status, and sensors values.
-
/sbg/ekf_euler
sbg_driver/SbgEkfEulerComputed orientation using Euler angles.
-
/sbg/ekf_quat
sbg_driver/SbgEkfQuatComputed orientation using Quaternion.
-
/sbg/ekf_nav
sbg_driver/SbgEkfNavComputed navigation data.
-
/sbg/mag
sbg_driver/SbgMagCalibrated magnetic field measurement.
-
/sbg/mag_calib
sbg_driver/SbgMagCalibMagnetometer calibration data.
-
/sbg/ship_motion
sbg_driver/SbgShipMotionHeave, surge and sway data.
-
/sbg/gps_vel
sbg_driver/SbgGpsVelGPS velocities from GPS receiver.
-
/sbg/gps_pos
sbg_driver/SbgGpsPosGPS positions from GPS receiver.
-
/sbg/gps_hdt
sbg_driver/SbgGpsHdtGPS true heading from dual antenna system.
-
/sbg/gps_raw
sbg_driver/SbgGpsRawGPS raw data for post processing.
-
/sbg/odo_vel
sbg_driver/SbgOdoVelOdometer velocity.
-
/sbg/event[ABCDE]
sbg_driver/SbgEventEvent on sync in the corresponding pin.
-
/sbg/air_data
sbg_driver/SbgAirDataAir data.
ROS standard topics
[!NOTE] Please update the driver configuration to enable standard ROS messages publication
output.ros_standard
. Also, the driver only publish standard ROS messages if the driver is setup to use ENU frame conventionoutput.use_enu
.
In order to define ROS standard topics, it requires sometimes several SBG messages, to be merged. For each ROS standard, you have to activate the needed SBG outputs.
-
/imu/data
sensor_msgs/ImuIMU data. Requires
/sbg/imu_data
and/sbg/ekf_quat
. -
/imu/temp
sensor_msgs/TemperatureIMU temperature data. Requires
/sbg/imu_data
. -
/imu/velocity
geometry_msgs/TwistStampedIMU velocity data. Requires
/sbg/imu_data
. -
/imu/mag
sensor_msgs/MagneticFieldIMU magnetic field. Requires
/sbg/mag
. -
/imu/pres
sensor_msgs/FluidPressureIMU pressure data. Requires
/sbg/air_data
. -
/imu/pos_ecef
geometry_msgs/PointStampedEarth-Centered Earth-Fixed position. Requires
/sbg/ekf_nav
. -
/imu/utc_ref
sensor_msgs/TimeReferenceUTC time reference. Requires
/sbg/utc_time
. -
/imu/nav_sat_fix
sensor_msgs/NavSatFixNavigation satellite fix for any Global Navigation Satellite System. Requires
/sbg/gps_pos
. -
/imu/odometry
nav_msgs/OdometryUTM projected position relative to the first valid INS position. Requires
/sbg/imu_data
and/sbg/ekv_nav
and either/sbg/ekf_euler
or/sbg/ekf_quat
. Disabled by default, setodometry.enable
in configuration file.
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/nmea
nmea_msgs/SentenceData from
/sbg/gps_pos
serialized into NMEA GGA format. Requires/sbg/gps_pos
.
Namespacentrip_client
and topic_namenmea
can be customized in .yaml config files.
Subscribed Topics
RTCM topics
The sbg_device
node can subscribe to RTCM topics published by third party ROS 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/rtcm
rtcm_msgs/MessageRTCM data from
/ntrip_client/rtcm
will be forwarded to the internal INS GNSS receiver.
Namespacentrip_client
and topic_namertcm
can 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_calibration
std_srvs/TriggerService to start/stop the magnetic calibration.
-
/sbg/mag_calibration_save
std_srvs/TriggerService to save in FLASH memory the latest computed magnetic field calibration.
HowTo
Configure the SBG device
The SBG Ros driver allows the user to configure the device before starting data parsing.
To do so, set the corresponding parameter in the used config file.
# Configuration of the device with ROS.
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.
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 ROS 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 ROS driver:
- For ELLIPSE, simply use the
sbgCenter
and inAssignment panel
,RTCM
should be set toPort A
. - For High Performance INS, either use the configuration web interface or the sbgInsRestApi.
- For ELLIPSE, simply use the
- Install and configure a third party node that broadcast RTCM corrections such as a NTRIP client
- Update the node config
yaml
file to setrtcm.subscribe
andnmea.publish
totrue
- If you use a different node to broadcast RTCM topics, you might have to update the config
yaml
file 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 ROS 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.
1) Make sure you have selected the desired 2D or 3D magnetic field calibration mode (calibration.mode
in the configuration yaml
file).
2) Start a new magnetic calibration session once you are ready to map the magnetic field:
roslaunch sbg_driver sbg_device_mag_calibration.launch
rosservice call /sbg/mag_calibration
success: True
message: “Magnetometer calibration process started.”
3) 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). 4) Once you believe you have covered enough orientations, compute a magnetic field calibration:
rosservice call /sbg/mag_calibration
success: True
message: “Magnetometer calibration is finished. See the output console to get calibration information.”
5) 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)
rosservice call /sbg/mag_calibration_save
success: True
message: “Magnetometer calibration has been uploaded to the device.”
6) 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
ROS 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 ROS 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"
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 ROS 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 ROS 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 |
Navigation Frame:
The navigation frame also referred by ROS as the cartesian representation is defined as follow:
NED Convention | ENU Convention |
---|---|
X North | X East |
Y East | Y North |
Z Down | Z Up |
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.
Changelog for package sbg_driver
3.2.0 (2024-10-09)
- Update README according to the latest changes
- Backported changes from ROS2 driver
- fix #70 build on Windows
- remove unused var
- update doc to build from sources
- Perform proper name resolution to make name remapping more convenient Fixes #75.
- Contributors: Michael Zemb, Richard Braun, Samuel Toledano, cledant
3.1.1 (2021-10-15)
- fix missing dependencies and build status link
- missing dep on nav_msgs, tf2_geometry_msgs, tf2_ros and tf2_msgs
- fix build status link in readme
- update doc with odometry message
- Contributors: Michael Zemb
3.1.0 (2021-10-06)
- Feature #44 - odometry output
- fix #66 - status description for SbgGpsHdt msg
- fix #66 - missing heading and pitch accuracies in sbgGpsHdt msg
- add ellipse D default configuration
- update README
- Contributors: Michael Zemb
3.0.0 (2021-08-31)
- Merge pull request #62 from SBG-Systems/devel Devel
- Merge pull request #61 from SBG-Systems/fix-frame-convention Fix frame convention errors
- Make sure only delta angles/velocities are used
- syntax fixes
- Improved comments & README file
- Fix missing checks on UTC / Unix time computation
- Updated sbgECom messages definitions
- Update README.md and releasePackage.md
- Clean up readme
- Fix position accuracy
- Replace pow by multiplication
- Complete README.md
- Fix bugs in message wrapper and complete message definitions
- Fix Z GPS velocity
- Fix frame convention errors
- Merge pull request #59 from SBG-Systems/fix-frame-id Fix param name
- Fix param name
- Fix inconsistent tab and spaces usages. Now all files are using spaces
- Add wrap 2PI
- Fix bugs
- Fix matrix accuracy
- Fix course
- wrapper: Fix ENU->NED for GPS messages
- warpper: Change createrVector3 names
- wrapper: Fix setter
- wrapper: Fix missing ENU conversion an add comment for cov
- wrapper: Fix regresion
- coding style : Remove tables
- publisher: Configure the wrapper before init the publisher
- main: Fix loopFrequency type
- config: Restore output configuration
- config: Replace enu by use_enu
- enu: Replace enu by use_enu and rename frame convertion function
- frame_id: Change default value
- clean up
- #51 - Correctly fill convariances parameters
- project: Update maintainer
- config: Update parameters
- #45-#50 - Add parameters to set frame ID and ENU convention
- #48 - # 52 Add a parameter to select header stamp source and read ROS time when publishing the message
- #47 Remove node ros::Rate period auto computation and only read it from a node parameter
- clean up: Remove blank spaces
- Merge pull request #35 from ShepelIlya/patch-1 Fixed time_stamp value initializing in SbgEkfNavMessage.
- Added/updated license to MIT
- Updated maintainer
- Fixed timeStamp value initializing in SbgEkfNavMessage.
- Contributors: Michael Zemb, Raphael Siryani, ShepelIlya, bsaussay, rsiryani
2.0.3 (2020-04-01)
- Improve matrix handling
- Fix body velocity computation (Issue #31)
2.0.1 (2020-01-24)
- Improve vector handling
- Fix include file (Issue #26)
2.0.0 (2020-01-06)
- Fix integer type
- Update sbgECom messages (AirData, ImuShort)
- Update sbgECom library to 1.11.920-stable
- Improve numeric type
- Improve configuration applier
- Improve error handling
- Code improvement
- Improve device configuration
- Update changelog
- Update and improve README.md
- Update magnetic services
- Improve message timestamping
- Add some ROS standard sensor messages (Issue #17)
- Comply file structure to ROS best pratices
- Add a processing time to improve message handling
- Add udev rules to documentation (Issue #21)
- Improve magnetometers calibration
- Update maintainer of the package (Issue #20)
- Enable/Disable the configuration of the device (Issue #19)
- Define unified class and launch files for all SBG devices
- Define classes for device configuration
- Merge pull request #18 from SBG-Systems/messagePublisherRework
- Integrate new message publisher to the Ellipse class (Issue #15)
- Define a class to publish messages
- Define class to wrap SBG logs to Ros messages
- Merge pull request #16 from SBG-Systems/v4.3
- [src] Update SDK version + add LogE support
- Merge pull request #13 from nicolaje/remove-non-ascii-char
- [conf] Removed non-ASCII characters, (Issue #8)
- [msg] Remove non ascii characters
1.1.7 (2018-07-19)
- [src] Change SbgEkfEuler comments
- [src] Move .h to include folder + test new method for time saving in calib
1.1.6 (2018-03-18)
- [config, src] Update default port for gps aiding (Ellipse-E) + add save & reboot for mag calibration
- [build] Add include for debian jessie arm64 build issue
1.1.5 (2018-03-12 23:49)
- [src] Update mag calibration
1.1.4 (2018-03-12 23:10)
- [catkin] Update install launch & config
- [src] Update library + Correction bugs
1.1.3 (2018-03-12 11:46)
- Update dependencies to std_srvs
1.1.2 (2018-03-12 09:54)
- [ChangeLog] Remove
- [ChangeLog] Update
- [Changelog] Test
- [test] Changelog
- [Changelog] Update
- [CMake] Correction of message dependency
1.1.1 (2018-03-11)
- [xml] Update version number
- [src] Correction of small bugs + add publisher only on activated log
- [merge] Finalize merge from devel branch (master divergence issue)
- [lib] Update the library sbgECom version after merging from devel
- [Merge]
- Merge branch 'master' of https://github.com/ENSTABretagneRobotics/sbg_ros_driver
- [src] Update doc
- [src] Update magnetic calibration node
- Revert "1.0.7" This reverts commit 8f57f9e578937ac23383e39ebf616d1039384b09.
- Update README
- Merge pull request #2 from rpng/master Upgrade sbg_ros_driver
- Moved the logging function into the class
- Added - Start of heading code
- Refactor and added new publishers
- Increased rates
- refactoring use a class for callbacks changed callbacks around a bit, now shows raw data rather than ekf logs
- use gps log message for NavSatFix message
- add extra debug messages
- use private namespace
- modified launch file moved to launch folder and added optional arguments
- updated sbgECom library
1.1.0 (2018-03-10)
- [src] Update Events
- [src] Add params
- [src] Update (add configuration of the ellipse)
- [src] Update messages
- [src] Start creating sbg messages
1.0.7 (2017-04-01)
- [src][minor] Correct launch file
1.0.6 (2017-03-31)
- CHANGELOG
- [src] Add launch example
- [src] Change imu data & add gyroscopes
1.0.5 (2016-11-17 00:04)
1.0.4 (2016-11-17 00:02)
1.0.3 (2016-11-16 23:59)
- [src][minor] Correction of Project name in CmakeList
1.0.2 (2016-11-16 22:58)
- [doc] minor
- [doc] Update Package
1.0.1 (2016-11-16 22:30)
- [doc] Update package version to 1.0.0
- [doc] Add Changelog
- [src] Update of deprecated function
- [src] Update (correcting cmake sub project)
- [src] Correct cmake subdirectory issue
- Initial commit
Wiki Tutorials
Package Dependencies
Deps | Name |
---|---|
roscpp | |
sensor_msgs | |
std_msgs | |
std_srvs | |
geometry_msgs | |
message_generation | |
nav_msgs | |
tf2_ros | |
tf2_msgs | |
tf2_geometry_msgs | |
rtcm_msgs | |
nmea_msgs | |
catkin | |
message_runtime |
System Dependencies
Dependant Packages
Launch files
Messages
- msg/SbgEkfQuat.msg
- msg/SbgStatusCom.msg
- msg/SbgGpsVel.msg
- msg/SbgMag.msg
- msg/SbgShipMotionStatus.msg
- msg/SbgImuData.msg
- msg/SbgUtcTimeStatus.msg
- msg/SbgShipMotion.msg
- msg/SbgGpsPosStatus.msg
- msg/SbgImuStatus.msg
- msg/SbgStatus.msg
- msg/SbgStatusAiding.msg
- msg/SbgUtcTime.msg
- msg/SbgAirDataStatus.msg
- msg/SbgEkfNav.msg
- msg/SbgEkfEuler.msg
- msg/SbgMagCalib.msg
- msg/SbgGpsRaw.msg
- msg/SbgGpsHdt.msg
- msg/SbgEkfStatus.msg
- msg/SbgStatusGeneral.msg
- msg/SbgGpsPos.msg
- msg/SbgAirData.msg
- msg/SbgMagStatus.msg
- msg/SbgOdoVel.msg
- msg/SbgImuShort.msg
- msg/SbgGpsVelStatus.msg
- msg/SbgEvent.msg
Services
Plugins
Recent questions tagged sbg_driver at Robotics Stack Exchange
sbg_driver package from sbg_driver reposbg_driver |
|
Package Summary
Tags | No category tags. |
Version | 3.2.0 |
License | MIT |
Build type | CATKIN |
Use | RECOMMENDED |
Repository Summary
Checkout URI | https://github.com/SBG-Systems/sbg_ros_driver.git |
VCS Type | git |
VCS Version | master |
Last Updated | 2024-10-09 |
Dev Status | MAINTAINED |
CI status | Continuous Integration |
Released | RELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- SBG Systems
Authors
- SBG Systems
sbg_driver
ROS 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 the following features:
- Configure ELLIPSE products using yaml files (see note below)
- Parse IMU/AHRS/INS/GNSS using the sbgECom protocol
- Publish standard ROS 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
[!NOTE] Only ELLIPSE devices can be configured from the ROS driver. For High Performance INS such as EKINOX, APOGEE and QUANTA, please use the sbgInsRestApi
Installation
Installation from Packages
User can install the sbg_ros_driver through the standard ROS installation system.
- Noetic
sudo apt-get install ros-noetic-sbg-driver
Building from sources
Dependencies
- Robot Operating System (ROS)
- sbgECom C Library (embeds v1.11.920-stable - compatible with ELLIPSE firmware above 1.7)
- Boost C++ Library
Building
- Clone the repository (use a Release version)
cd catkin_ws/src
git clone -b master https://github.com/SBG-Systems/sbg_ros_driver.git
- Install dependencies
cd ..
rosdep install --from-paths src --ignore-src -r -y
- Build using the normal ROS catkin build system
source /opt/ros/${ROS_DISTRO}/setup.bash
catkin_make
Usage
Source the generated setup environment
source devel/setup.bash
To run the default Ros node with the default configuration
roslaunch sbg_driver sbg_device.launch
To run the magnetic calibration node
roslaunch sbg_driver sbg_device_mag_calibration.launch
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 ROS node, so it has to be previously configured (manually or with the ROS node).
It defines a few outputs for the device:-
/sbg/imu_data
,/sbg/ekf_quat
at 25Hz - ROS standard outputs
/imu/data
,/imu/velocity
,/imu/temp
at 25Hz -
/sbg/status
,/sbg/utc_time
and/imu/utc_ref
at 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 ROS node, so it has to be previously configured (manually or with the ROS node).
It defines a few outputs for the device:-
/sbg/imu_data
,/sbg/ekf_quat
at 25Hz - ROS standard outputs
/imu/data
,/imu/velocity
,/imu/temp
at 25Hz -
/sbg/status
,/sbg/utc_time
and/imu/utc_ref
at 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.yaml
configuration. -
sbg_device_mag_calibration_launch.py Launch the sbg_device_mag node to calibrate the magnetometers, and load the
ellipse_E_default.yaml
configuration.
Nodes
sbg_device node
The sbg_device
node handles the communication with the connected device, publishes the SBG output to the ROS environment and subscribes to useful topics such as RTCM data streams.
Published Topics
SBG Systems specific topics
SBG Systems has defined proprietary ROS 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.
-
/sbg/status
sbg_driver/SbgStatusProvides information about the general status (Communication, Aiding, etc..).
-
/sbg/utc_time
sbg_driver/SbgUtcTimeProvides UTC time reference.
-
/sbg/imu_data
sbg_driver/SbgImuDataIMU status, and sensors values.
-
/sbg/ekf_euler
sbg_driver/SbgEkfEulerComputed orientation using Euler angles.
-
/sbg/ekf_quat
sbg_driver/SbgEkfQuatComputed orientation using Quaternion.
-
/sbg/ekf_nav
sbg_driver/SbgEkfNavComputed navigation data.
-
/sbg/mag
sbg_driver/SbgMagCalibrated magnetic field measurement.
-
/sbg/mag_calib
sbg_driver/SbgMagCalibMagnetometer calibration data.
-
/sbg/ship_motion
sbg_driver/SbgShipMotionHeave, surge and sway data.
-
/sbg/gps_vel
sbg_driver/SbgGpsVelGPS velocities from GPS receiver.
-
/sbg/gps_pos
sbg_driver/SbgGpsPosGPS positions from GPS receiver.
-
/sbg/gps_hdt
sbg_driver/SbgGpsHdtGPS true heading from dual antenna system.
-
/sbg/gps_raw
sbg_driver/SbgGpsRawGPS raw data for post processing.
-
/sbg/odo_vel
sbg_driver/SbgOdoVelOdometer velocity.
-
/sbg/event[ABCDE]
sbg_driver/SbgEventEvent on sync in the corresponding pin.
-
/sbg/air_data
sbg_driver/SbgAirDataAir data.
ROS standard topics
[!NOTE] Please update the driver configuration to enable standard ROS messages publication
output.ros_standard
. Also, the driver only publish standard ROS messages if the driver is setup to use ENU frame conventionoutput.use_enu
.
In order to define ROS standard topics, it requires sometimes several SBG messages, to be merged. For each ROS standard, you have to activate the needed SBG outputs.
-
/imu/data
sensor_msgs/ImuIMU data. Requires
/sbg/imu_data
and/sbg/ekf_quat
. -
/imu/temp
sensor_msgs/TemperatureIMU temperature data. Requires
/sbg/imu_data
. -
/imu/velocity
geometry_msgs/TwistStampedIMU velocity data. Requires
/sbg/imu_data
. -
/imu/mag
sensor_msgs/MagneticFieldIMU magnetic field. Requires
/sbg/mag
. -
/imu/pres
sensor_msgs/FluidPressureIMU pressure data. Requires
/sbg/air_data
. -
/imu/pos_ecef
geometry_msgs/PointStampedEarth-Centered Earth-Fixed position. Requires
/sbg/ekf_nav
. -
/imu/utc_ref
sensor_msgs/TimeReferenceUTC time reference. Requires
/sbg/utc_time
. -
/imu/nav_sat_fix
sensor_msgs/NavSatFixNavigation satellite fix for any Global Navigation Satellite System. Requires
/sbg/gps_pos
. -
/imu/odometry
nav_msgs/OdometryUTM projected position relative to the first valid INS position. Requires
/sbg/imu_data
and/sbg/ekv_nav
and either/sbg/ekf_euler
or/sbg/ekf_quat
. Disabled by default, setodometry.enable
in configuration file.
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/nmea
nmea_msgs/SentenceData from
/sbg/gps_pos
serialized into NMEA GGA format. Requires/sbg/gps_pos
.
Namespacentrip_client
and topic_namenmea
can be customized in .yaml config files.
Subscribed Topics
RTCM topics
The sbg_device
node can subscribe to RTCM topics published by third party ROS 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/rtcm
rtcm_msgs/MessageRTCM data from
/ntrip_client/rtcm
will be forwarded to the internal INS GNSS receiver.
Namespacentrip_client
and topic_namertcm
can 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_calibration
std_srvs/TriggerService to start/stop the magnetic calibration.
-
/sbg/mag_calibration_save
std_srvs/TriggerService to save in FLASH memory the latest computed magnetic field calibration.
HowTo
Configure the SBG device
The SBG Ros driver allows the user to configure the device before starting data parsing.
To do so, set the corresponding parameter in the used config file.
# Configuration of the device with ROS.
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.
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 ROS 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 ROS driver:
- For ELLIPSE, simply use the
sbgCenter
and inAssignment panel
,RTCM
should be set toPort A
. - For High Performance INS, either use the configuration web interface or the sbgInsRestApi.
- For ELLIPSE, simply use the
- Install and configure a third party node that broadcast RTCM corrections such as a NTRIP client
- Update the node config
yaml
file to setrtcm.subscribe
andnmea.publish
totrue
- If you use a different node to broadcast RTCM topics, you might have to update the config
yaml
file 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 ROS 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.
1) Make sure you have selected the desired 2D or 3D magnetic field calibration mode (calibration.mode
in the configuration yaml
file).
2) Start a new magnetic calibration session once you are ready to map the magnetic field:
roslaunch sbg_driver sbg_device_mag_calibration.launch
rosservice call /sbg/mag_calibration
success: True
message: “Magnetometer calibration process started.”
3) 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). 4) Once you believe you have covered enough orientations, compute a magnetic field calibration:
rosservice call /sbg/mag_calibration
success: True
message: “Magnetometer calibration is finished. See the output console to get calibration information.”
5) 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)
rosservice call /sbg/mag_calibration_save
success: True
message: “Magnetometer calibration has been uploaded to the device.”
6) 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
ROS 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 ROS 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"
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 ROS 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 ROS 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 |
Navigation Frame:
The navigation frame also referred by ROS as the cartesian representation is defined as follow:
NED Convention | ENU Convention |
---|---|
X North | X East |
Y East | Y North |
Z Down | Z Up |
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.
Changelog for package sbg_driver
3.2.0 (2024-10-09)
- Update README according to the latest changes
- Backported changes from ROS2 driver
- fix #70 build on Windows
- remove unused var
- update doc to build from sources
- Perform proper name resolution to make name remapping more convenient Fixes #75.
- Contributors: Michael Zemb, Richard Braun, Samuel Toledano, cledant
3.1.1 (2021-10-15)
- fix missing dependencies and build status link
- missing dep on nav_msgs, tf2_geometry_msgs, tf2_ros and tf2_msgs
- fix build status link in readme
- update doc with odometry message
- Contributors: Michael Zemb
3.1.0 (2021-10-06)
- Feature #44 - odometry output
- fix #66 - status description for SbgGpsHdt msg
- fix #66 - missing heading and pitch accuracies in sbgGpsHdt msg
- add ellipse D default configuration
- update README
- Contributors: Michael Zemb
3.0.0 (2021-08-31)
- Merge pull request #62 from SBG-Systems/devel Devel
- Merge pull request #61 from SBG-Systems/fix-frame-convention Fix frame convention errors
- Make sure only delta angles/velocities are used
- syntax fixes
- Improved comments & README file
- Fix missing checks on UTC / Unix time computation
- Updated sbgECom messages definitions
- Update README.md and releasePackage.md
- Clean up readme
- Fix position accuracy
- Replace pow by multiplication
- Complete README.md
- Fix bugs in message wrapper and complete message definitions
- Fix Z GPS velocity
- Fix frame convention errors
- Merge pull request #59 from SBG-Systems/fix-frame-id Fix param name
- Fix param name
- Fix inconsistent tab and spaces usages. Now all files are using spaces
- Add wrap 2PI
- Fix bugs
- Fix matrix accuracy
- Fix course
- wrapper: Fix ENU->NED for GPS messages
- warpper: Change createrVector3 names
- wrapper: Fix setter
- wrapper: Fix missing ENU conversion an add comment for cov
- wrapper: Fix regresion
- coding style : Remove tables
- publisher: Configure the wrapper before init the publisher
- main: Fix loopFrequency type
- config: Restore output configuration
- config: Replace enu by use_enu
- enu: Replace enu by use_enu and rename frame convertion function
- frame_id: Change default value
- clean up
- #51 - Correctly fill convariances parameters
- project: Update maintainer
- config: Update parameters
- #45-#50 - Add parameters to set frame ID and ENU convention
- #48 - # 52 Add a parameter to select header stamp source and read ROS time when publishing the message
- #47 Remove node ros::Rate period auto computation and only read it from a node parameter
- clean up: Remove blank spaces
- Merge pull request #35 from ShepelIlya/patch-1 Fixed time_stamp value initializing in SbgEkfNavMessage.
- Added/updated license to MIT
- Updated maintainer
- Fixed timeStamp value initializing in SbgEkfNavMessage.
- Contributors: Michael Zemb, Raphael Siryani, ShepelIlya, bsaussay, rsiryani
2.0.3 (2020-04-01)
- Improve matrix handling
- Fix body velocity computation (Issue #31)
2.0.1 (2020-01-24)
- Improve vector handling
- Fix include file (Issue #26)
2.0.0 (2020-01-06)
- Fix integer type
- Update sbgECom messages (AirData, ImuShort)
- Update sbgECom library to 1.11.920-stable
- Improve numeric type
- Improve configuration applier
- Improve error handling
- Code improvement
- Improve device configuration
- Update changelog
- Update and improve README.md
- Update magnetic services
- Improve message timestamping
- Add some ROS standard sensor messages (Issue #17)
- Comply file structure to ROS best pratices
- Add a processing time to improve message handling
- Add udev rules to documentation (Issue #21)
- Improve magnetometers calibration
- Update maintainer of the package (Issue #20)
- Enable/Disable the configuration of the device (Issue #19)
- Define unified class and launch files for all SBG devices
- Define classes for device configuration
- Merge pull request #18 from SBG-Systems/messagePublisherRework
- Integrate new message publisher to the Ellipse class (Issue #15)
- Define a class to publish messages
- Define class to wrap SBG logs to Ros messages
- Merge pull request #16 from SBG-Systems/v4.3
- [src] Update SDK version + add LogE support
- Merge pull request #13 from nicolaje/remove-non-ascii-char
- [conf] Removed non-ASCII characters, (Issue #8)
- [msg] Remove non ascii characters
1.1.7 (2018-07-19)
- [src] Change SbgEkfEuler comments
- [src] Move .h to include folder + test new method for time saving in calib
1.1.6 (2018-03-18)
- [config, src] Update default port for gps aiding (Ellipse-E) + add save & reboot for mag calibration
- [build] Add include for debian jessie arm64 build issue
1.1.5 (2018-03-12 23:49)
- [src] Update mag calibration
1.1.4 (2018-03-12 23:10)
- [catkin] Update install launch & config
- [src] Update library + Correction bugs
1.1.3 (2018-03-12 11:46)
- Update dependencies to std_srvs
1.1.2 (2018-03-12 09:54)
- [ChangeLog] Remove
- [ChangeLog] Update
- [Changelog] Test
- [test] Changelog
- [Changelog] Update
- [CMake] Correction of message dependency
1.1.1 (2018-03-11)
- [xml] Update version number
- [src] Correction of small bugs + add publisher only on activated log
- [merge] Finalize merge from devel branch (master divergence issue)
- [lib] Update the library sbgECom version after merging from devel
- [Merge]
- Merge branch 'master' of https://github.com/ENSTABretagneRobotics/sbg_ros_driver
- [src] Update doc
- [src] Update magnetic calibration node
- Revert "1.0.7" This reverts commit 8f57f9e578937ac23383e39ebf616d1039384b09.
- Update README
- Merge pull request #2 from rpng/master Upgrade sbg_ros_driver
- Moved the logging function into the class
- Added - Start of heading code
- Refactor and added new publishers
- Increased rates
- refactoring use a class for callbacks changed callbacks around a bit, now shows raw data rather than ekf logs
- use gps log message for NavSatFix message
- add extra debug messages
- use private namespace
- modified launch file moved to launch folder and added optional arguments
- updated sbgECom library
1.1.0 (2018-03-10)
- [src] Update Events
- [src] Add params
- [src] Update (add configuration of the ellipse)
- [src] Update messages
- [src] Start creating sbg messages
1.0.7 (2017-04-01)
- [src][minor] Correct launch file
1.0.6 (2017-03-31)
- CHANGELOG
- [src] Add launch example
- [src] Change imu data & add gyroscopes
1.0.5 (2016-11-17 00:04)
1.0.4 (2016-11-17 00:02)
1.0.3 (2016-11-16 23:59)
- [src][minor] Correction of Project name in CmakeList
1.0.2 (2016-11-16 22:58)
- [doc] minor
- [doc] Update Package
1.0.1 (2016-11-16 22:30)
- [doc] Update package version to 1.0.0
- [doc] Add Changelog
- [src] Update of deprecated function
- [src] Update (correcting cmake sub project)
- [src] Correct cmake subdirectory issue
- Initial commit
Wiki Tutorials
Package Dependencies
Deps | Name |
---|---|
roscpp | |
sensor_msgs | |
std_msgs | |
std_srvs | |
geometry_msgs | |
message_generation | |
nav_msgs | |
tf2_ros | |
tf2_msgs | |
tf2_geometry_msgs | |
rtcm_msgs | |
nmea_msgs | |
catkin | |
message_runtime |
System Dependencies
Dependant Packages
Launch files
Messages
- msg/SbgEkfQuat.msg
- msg/SbgStatusCom.msg
- msg/SbgGpsVel.msg
- msg/SbgMag.msg
- msg/SbgShipMotionStatus.msg
- msg/SbgImuData.msg
- msg/SbgUtcTimeStatus.msg
- msg/SbgShipMotion.msg
- msg/SbgGpsPosStatus.msg
- msg/SbgImuStatus.msg
- msg/SbgStatus.msg
- msg/SbgStatusAiding.msg
- msg/SbgUtcTime.msg
- msg/SbgAirDataStatus.msg
- msg/SbgEkfNav.msg
- msg/SbgEkfEuler.msg
- msg/SbgMagCalib.msg
- msg/SbgGpsRaw.msg
- msg/SbgGpsHdt.msg
- msg/SbgEkfStatus.msg
- msg/SbgStatusGeneral.msg
- msg/SbgGpsPos.msg
- msg/SbgAirData.msg
- msg/SbgMagStatus.msg
- msg/SbgOdoVel.msg
- msg/SbgImuShort.msg
- msg/SbgGpsVelStatus.msg
- msg/SbgEvent.msg
Services
Plugins
Recent questions tagged sbg_driver at Robotics Stack Exchange
sbg_driver package from sbg_driver reposbg_driver |
|
Package Summary
Tags | No category tags. |
Version | 3.2.0 |
License | MIT |
Build type | CATKIN |
Use | RECOMMENDED |
Repository Summary
Checkout URI | https://github.com/SBG-Systems/sbg_ros_driver.git |
VCS Type | git |
VCS Version | master |
Last Updated | 2024-10-09 |
Dev Status | MAINTAINED |
CI status | Continuous Integration : 0 / 0 |
Released | RELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- SBG Systems
Authors
- SBG Systems
sbg_driver
ROS 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 the following features:
- Configure ELLIPSE products using yaml files (see note below)
- Parse IMU/AHRS/INS/GNSS using the sbgECom protocol
- Publish standard ROS 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
[!NOTE] Only ELLIPSE devices can be configured from the ROS driver. For High Performance INS such as EKINOX, APOGEE and QUANTA, please use the sbgInsRestApi
Installation
Installation from Packages
User can install the sbg_ros_driver through the standard ROS installation system.
- Noetic
sudo apt-get install ros-noetic-sbg-driver
Building from sources
Dependencies
- Robot Operating System (ROS)
- sbgECom C Library (embeds v1.11.920-stable - compatible with ELLIPSE firmware above 1.7)
- Boost C++ Library
Building
- Clone the repository (use a Release version)
cd catkin_ws/src
git clone -b master https://github.com/SBG-Systems/sbg_ros_driver.git
- Install dependencies
cd ..
rosdep install --from-paths src --ignore-src -r -y
- Build using the normal ROS catkin build system
source /opt/ros/${ROS_DISTRO}/setup.bash
catkin_make
Usage
Source the generated setup environment
source devel/setup.bash
To run the default Ros node with the default configuration
roslaunch sbg_driver sbg_device.launch
To run the magnetic calibration node
roslaunch sbg_driver sbg_device_mag_calibration.launch
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 ROS node, so it has to be previously configured (manually or with the ROS node).
It defines a few outputs for the device:-
/sbg/imu_data
,/sbg/ekf_quat
at 25Hz - ROS standard outputs
/imu/data
,/imu/velocity
,/imu/temp
at 25Hz -
/sbg/status
,/sbg/utc_time
and/imu/utc_ref
at 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 ROS node, so it has to be previously configured (manually or with the ROS node).
It defines a few outputs for the device:-
/sbg/imu_data
,/sbg/ekf_quat
at 25Hz - ROS standard outputs
/imu/data
,/imu/velocity
,/imu/temp
at 25Hz -
/sbg/status
,/sbg/utc_time
and/imu/utc_ref
at 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.yaml
configuration. -
sbg_device_mag_calibration_launch.py Launch the sbg_device_mag node to calibrate the magnetometers, and load the
ellipse_E_default.yaml
configuration.
Nodes
sbg_device node
The sbg_device
node handles the communication with the connected device, publishes the SBG output to the ROS environment and subscribes to useful topics such as RTCM data streams.
Published Topics
SBG Systems specific topics
SBG Systems has defined proprietary ROS 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.
-
/sbg/status
sbg_driver/SbgStatusProvides information about the general status (Communication, Aiding, etc..).
-
/sbg/utc_time
sbg_driver/SbgUtcTimeProvides UTC time reference.
-
/sbg/imu_data
sbg_driver/SbgImuDataIMU status, and sensors values.
-
/sbg/ekf_euler
sbg_driver/SbgEkfEulerComputed orientation using Euler angles.
-
/sbg/ekf_quat
sbg_driver/SbgEkfQuatComputed orientation using Quaternion.
-
/sbg/ekf_nav
sbg_driver/SbgEkfNavComputed navigation data.
-
/sbg/mag
sbg_driver/SbgMagCalibrated magnetic field measurement.
-
/sbg/mag_calib
sbg_driver/SbgMagCalibMagnetometer calibration data.
-
/sbg/ship_motion
sbg_driver/SbgShipMotionHeave, surge and sway data.
-
/sbg/gps_vel
sbg_driver/SbgGpsVelGPS velocities from GPS receiver.
-
/sbg/gps_pos
sbg_driver/SbgGpsPosGPS positions from GPS receiver.
-
/sbg/gps_hdt
sbg_driver/SbgGpsHdtGPS true heading from dual antenna system.
-
/sbg/gps_raw
sbg_driver/SbgGpsRawGPS raw data for post processing.
-
/sbg/odo_vel
sbg_driver/SbgOdoVelOdometer velocity.
-
/sbg/event[ABCDE]
sbg_driver/SbgEventEvent on sync in the corresponding pin.
-
/sbg/air_data
sbg_driver/SbgAirDataAir data.
ROS standard topics
[!NOTE] Please update the driver configuration to enable standard ROS messages publication
output.ros_standard
. Also, the driver only publish standard ROS messages if the driver is setup to use ENU frame conventionoutput.use_enu
.
In order to define ROS standard topics, it requires sometimes several SBG messages, to be merged. For each ROS standard, you have to activate the needed SBG outputs.
-
/imu/data
sensor_msgs/ImuIMU data. Requires
/sbg/imu_data
and/sbg/ekf_quat
. -
/imu/temp
sensor_msgs/TemperatureIMU temperature data. Requires
/sbg/imu_data
. -
/imu/velocity
geometry_msgs/TwistStampedIMU velocity data. Requires
/sbg/imu_data
. -
/imu/mag
sensor_msgs/MagneticFieldIMU magnetic field. Requires
/sbg/mag
. -
/imu/pres
sensor_msgs/FluidPressureIMU pressure data. Requires
/sbg/air_data
. -
/imu/pos_ecef
geometry_msgs/PointStampedEarth-Centered Earth-Fixed position. Requires
/sbg/ekf_nav
. -
/imu/utc_ref
sensor_msgs/TimeReferenceUTC time reference. Requires
/sbg/utc_time
. -
/imu/nav_sat_fix
sensor_msgs/NavSatFixNavigation satellite fix for any Global Navigation Satellite System. Requires
/sbg/gps_pos
. -
/imu/odometry
nav_msgs/OdometryUTM projected position relative to the first valid INS position. Requires
/sbg/imu_data
and/sbg/ekv_nav
and either/sbg/ekf_euler
or/sbg/ekf_quat
. Disabled by default, setodometry.enable
in configuration file.
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/nmea
nmea_msgs/SentenceData from
/sbg/gps_pos
serialized into NMEA GGA format. Requires/sbg/gps_pos
.
Namespacentrip_client
and topic_namenmea
can be customized in .yaml config files.
Subscribed Topics
RTCM topics
The sbg_device
node can subscribe to RTCM topics published by third party ROS 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/rtcm
rtcm_msgs/MessageRTCM data from
/ntrip_client/rtcm
will be forwarded to the internal INS GNSS receiver.
Namespacentrip_client
and topic_namertcm
can 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_calibration
std_srvs/TriggerService to start/stop the magnetic calibration.
-
/sbg/mag_calibration_save
std_srvs/TriggerService to save in FLASH memory the latest computed magnetic field calibration.
HowTo
Configure the SBG device
The SBG Ros driver allows the user to configure the device before starting data parsing.
To do so, set the corresponding parameter in the used config file.
# Configuration of the device with ROS.
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.
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 ROS 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 ROS driver:
- For ELLIPSE, simply use the
sbgCenter
and inAssignment panel
,RTCM
should be set toPort A
. - For High Performance INS, either use the configuration web interface or the sbgInsRestApi.
- For ELLIPSE, simply use the
- Install and configure a third party node that broadcast RTCM corrections such as a NTRIP client
- Update the node config
yaml
file to setrtcm.subscribe
andnmea.publish
totrue
- If you use a different node to broadcast RTCM topics, you might have to update the config
yaml
file 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 ROS 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.
1) Make sure you have selected the desired 2D or 3D magnetic field calibration mode (calibration.mode
in the configuration yaml
file).
2) Start a new magnetic calibration session once you are ready to map the magnetic field:
roslaunch sbg_driver sbg_device_mag_calibration.launch
rosservice call /sbg/mag_calibration
success: True
message: “Magnetometer calibration process started.”
3) 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). 4) Once you believe you have covered enough orientations, compute a magnetic field calibration:
rosservice call /sbg/mag_calibration
success: True
message: “Magnetometer calibration is finished. See the output console to get calibration information.”
5) 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)
rosservice call /sbg/mag_calibration_save
success: True
message: “Magnetometer calibration has been uploaded to the device.”
6) 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
ROS 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 ROS 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"
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 ROS 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 ROS 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 |
Navigation Frame:
The navigation frame also referred by ROS as the cartesian representation is defined as follow:
NED Convention | ENU Convention |
---|---|
X North | X East |
Y East | Y North |
Z Down | Z Up |
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.
Changelog for package sbg_driver
3.2.0 (2024-10-09)
- Update README according to the latest changes
- Backported changes from ROS2 driver
- fix #70 build on Windows
- remove unused var
- update doc to build from sources
- Perform proper name resolution to make name remapping more convenient Fixes #75.
- Contributors: Michael Zemb, Richard Braun, Samuel Toledano, cledant
3.1.1 (2021-10-15)
- fix missing dependencies and build status link
- missing dep on nav_msgs, tf2_geometry_msgs, tf2_ros and tf2_msgs
- fix build status link in readme
- update doc with odometry message
- Contributors: Michael Zemb
3.1.0 (2021-10-06)
- Feature #44 - odometry output
- fix #66 - status description for SbgGpsHdt msg
- fix #66 - missing heading and pitch accuracies in sbgGpsHdt msg
- add ellipse D default configuration
- update README
- Contributors: Michael Zemb
3.0.0 (2021-08-31)
- Merge pull request #62 from SBG-Systems/devel Devel
- Merge pull request #61 from SBG-Systems/fix-frame-convention Fix frame convention errors
- Make sure only delta angles/velocities are used
- syntax fixes
- Improved comments & README file
- Fix missing checks on UTC / Unix time computation
- Updated sbgECom messages definitions
- Update README.md and releasePackage.md
- Clean up readme
- Fix position accuracy
- Replace pow by multiplication
- Complete README.md
- Fix bugs in message wrapper and complete message definitions
- Fix Z GPS velocity
- Fix frame convention errors
- Merge pull request #59 from SBG-Systems/fix-frame-id Fix param name
- Fix param name
- Fix inconsistent tab and spaces usages. Now all files are using spaces
- Add wrap 2PI
- Fix bugs
- Fix matrix accuracy
- Fix course
- wrapper: Fix ENU->NED for GPS messages
- warpper: Change createrVector3 names
- wrapper: Fix setter
- wrapper: Fix missing ENU conversion an add comment for cov
- wrapper: Fix regresion
- coding style : Remove tables
- publisher: Configure the wrapper before init the publisher
- main: Fix loopFrequency type
- config: Restore output configuration
- config: Replace enu by use_enu
- enu: Replace enu by use_enu and rename frame convertion function
- frame_id: Change default value
- clean up
- #51 - Correctly fill convariances parameters
- project: Update maintainer
- config: Update parameters
- #45-#50 - Add parameters to set frame ID and ENU convention
- #48 - # 52 Add a parameter to select header stamp source and read ROS time when publishing the message
- #47 Remove node ros::Rate period auto computation and only read it from a node parameter
- clean up: Remove blank spaces
- Merge pull request #35 from ShepelIlya/patch-1 Fixed time_stamp value initializing in SbgEkfNavMessage.
- Added/updated license to MIT
- Updated maintainer
- Fixed timeStamp value initializing in SbgEkfNavMessage.
- Contributors: Michael Zemb, Raphael Siryani, ShepelIlya, bsaussay, rsiryani
2.0.3 (2020-04-01)
- Improve matrix handling
- Fix body velocity computation (Issue #31)
2.0.1 (2020-01-24)
- Improve vector handling
- Fix include file (Issue #26)
2.0.0 (2020-01-06)
- Fix integer type
- Update sbgECom messages (AirData, ImuShort)
- Update sbgECom library to 1.11.920-stable
- Improve numeric type
- Improve configuration applier
- Improve error handling
- Code improvement
- Improve device configuration
- Update changelog
- Update and improve README.md
- Update magnetic services
- Improve message timestamping
- Add some ROS standard sensor messages (Issue #17)
- Comply file structure to ROS best pratices
- Add a processing time to improve message handling
- Add udev rules to documentation (Issue #21)
- Improve magnetometers calibration
- Update maintainer of the package (Issue #20)
- Enable/Disable the configuration of the device (Issue #19)
- Define unified class and launch files for all SBG devices
- Define classes for device configuration
- Merge pull request #18 from SBG-Systems/messagePublisherRework
- Integrate new message publisher to the Ellipse class (Issue #15)
- Define a class to publish messages
- Define class to wrap SBG logs to Ros messages
- Merge pull request #16 from SBG-Systems/v4.3
- [src] Update SDK version + add LogE support
- Merge pull request #13 from nicolaje/remove-non-ascii-char
- [conf] Removed non-ASCII characters, (Issue #8)
- [msg] Remove non ascii characters
1.1.7 (2018-07-19)
- [src] Change SbgEkfEuler comments
- [src] Move .h to include folder + test new method for time saving in calib
1.1.6 (2018-03-18)
- [config, src] Update default port for gps aiding (Ellipse-E) + add save & reboot for mag calibration
- [build] Add include for debian jessie arm64 build issue
1.1.5 (2018-03-12 23:49)
- [src] Update mag calibration
1.1.4 (2018-03-12 23:10)
- [catkin] Update install launch & config
- [src] Update library + Correction bugs
1.1.3 (2018-03-12 11:46)
- Update dependencies to std_srvs
1.1.2 (2018-03-12 09:54)
- [ChangeLog] Remove
- [ChangeLog] Update
- [Changelog] Test
- [test] Changelog
- [Changelog] Update
- [CMake] Correction of message dependency
1.1.1 (2018-03-11)
- [xml] Update version number
- [src] Correction of small bugs + add publisher only on activated log
- [merge] Finalize merge from devel branch (master divergence issue)
- [lib] Update the library sbgECom version after merging from devel
- [Merge]
- Merge branch 'master' of https://github.com/ENSTABretagneRobotics/sbg_ros_driver
- [src] Update doc
- [src] Update magnetic calibration node
- Revert "1.0.7" This reverts commit 8f57f9e578937ac23383e39ebf616d1039384b09.
- Update README
- Merge pull request #2 from rpng/master Upgrade sbg_ros_driver
- Moved the logging function into the class
- Added - Start of heading code
- Refactor and added new publishers
- Increased rates
- refactoring use a class for callbacks changed callbacks around a bit, now shows raw data rather than ekf logs
- use gps log message for NavSatFix message
- add extra debug messages
- use private namespace
- modified launch file moved to launch folder and added optional arguments
- updated sbgECom library
1.1.0 (2018-03-10)
- [src] Update Events
- [src] Add params
- [src] Update (add configuration of the ellipse)
- [src] Update messages
- [src] Start creating sbg messages
1.0.7 (2017-04-01)
- [src][minor] Correct launch file
1.0.6 (2017-03-31)
- CHANGELOG
- [src] Add launch example
- [src] Change imu data & add gyroscopes
1.0.5 (2016-11-17 00:04)
1.0.4 (2016-11-17 00:02)
1.0.3 (2016-11-16 23:59)
- [src][minor] Correction of Project name in CmakeList
1.0.2 (2016-11-16 22:58)
- [doc] minor
- [doc] Update Package
1.0.1 (2016-11-16 22:30)
- [doc] Update package version to 1.0.0
- [doc] Add Changelog
- [src] Update of deprecated function
- [src] Update (correcting cmake sub project)
- [src] Correct cmake subdirectory issue
- Initial commit
Wiki Tutorials
Package Dependencies
Deps | Name |
---|---|
roscpp | |
sensor_msgs | |
std_msgs | |
std_srvs | |
geometry_msgs | |
message_generation | |
nav_msgs | |
tf2_ros | |
tf2_msgs | |
tf2_geometry_msgs | |
rtcm_msgs | |
nmea_msgs | |
catkin | |
message_runtime |
System Dependencies
Dependant Packages
Launch files
Messages
- msg/SbgEkfQuat.msg
- msg/SbgStatusCom.msg
- msg/SbgGpsVel.msg
- msg/SbgMag.msg
- msg/SbgShipMotionStatus.msg
- msg/SbgImuData.msg
- msg/SbgUtcTimeStatus.msg
- msg/SbgShipMotion.msg
- msg/SbgGpsPosStatus.msg
- msg/SbgImuStatus.msg
- msg/SbgStatus.msg
- msg/SbgStatusAiding.msg
- msg/SbgUtcTime.msg
- msg/SbgAirDataStatus.msg
- msg/SbgEkfNav.msg
- msg/SbgEkfEuler.msg
- msg/SbgMagCalib.msg
- msg/SbgGpsRaw.msg
- msg/SbgGpsHdt.msg
- msg/SbgEkfStatus.msg
- msg/SbgStatusGeneral.msg
- msg/SbgGpsPos.msg
- msg/SbgAirData.msg
- msg/SbgMagStatus.msg
- msg/SbgOdoVel.msg
- msg/SbgImuShort.msg
- msg/SbgGpsVelStatus.msg
- msg/SbgEvent.msg