Home

Awesome

swiftnav-ros2

ROS 2 driver for Swift Navigation's GNSS/INS receivers and Starling Positioning Engine software.

Table of Contents

Features

ROS Topics

The driver receives Swift binary (SBP) messages (see GNSS Receiver Configuration for setting up the receiver) and publishes the following ROS topics:

Topic publication details are described below.

GpsFix

gps_msgs/msg/GPSFix

SBP Messages Used

Topic Publication

Topic publication depends on timestamp_source_gnss setting flag in the configuration file:

Topic Fields

ROS2 Message FieldSBP Message Data SourceNotes
header.stampUTC TIMESee Topic Publication for time stamping details
header.frame_id--Text from frame_name field in the settings.yaml configuration file
status.satellites_usedPOS LLH COV
status.satellite_used_prn[]--Not populated
status.satellites_visible<br>status.satellite_visible_prn[]<br>status.satellite_visible_z[]<br>status.satellite_visible_azimuth[]<br>status.satellite_visible_snr[]--Not populated
status.statusPOS LLH COVDead Reckoning (DR) position is reported as STATUS_FIX (0)
status.motion_sourceVEL NED COV
status.orientation_sourcePOS LLH COV
status.position_sourcePOS LLH COV
latitude<br>longitude<br>altitude<br>POS LLH COVZeros when the fix is invalid. If position is valid altitude is always present (i.e. never NaN).
trackVEL NED COV<br>or<br>ORIENT EULERIf ORIENT EULER message is present and yaw data valid, reports yaw. If yaw is invalid reports computed Course Over Ground from VEL NED COV message. VEL NED COV updates track only if horizontal speed is above the track_update_min_speed_mps setting in the settings file. When the track becomes invalid the last valid track is reported.
speedPOS LLH COVComputed horizontal (2D) speed
climbPOS LLH COV
pitch<br>rollORIENT EULER
dip--Not populated
timeGPS TIMEGPS time in seconds since 1980-01-06
gdop<br>pdop<br>hdop<br>vdop<br>tdopDOPSDOPs are published if the most recent SBP DOPS message is not older than 2 seconds.
err<br>err_horz<br>err_vertPOS LLH COV
err_trackVEL NED COV<br>or<br>ORIENT EULER
err_speed<br>err_climbVEL NED COV
err_time--Not populated
err_pitch<br>err_rollORIENT EULER
err_dip--Not populated
position_covariance<br>position_covariance_typePOS LLH COVCovariance, if valid, is always TYPE_KNOWN (full matrix).

NavSatFix

sensor_msgs/msg/NavSatFix

SBP Messages Used

Topic Publication

Topic publication depends on timestamp_source_gnss setting flag in the configuration file:

Topic Fields

ROS2 Message FieldSBP Message Data SourceNotes
header.stampUTC TIMESee Topic Publication for time stamping details
header.frame_id--Text from frame_name field in the settings.yaml configuration file
status.statusPOS LLH COVDead Reckoning (DR) position is reported as STATUS_FIX (0)
status.serviceMEASUREMENT STATEGNSS constellations from the last MEASUREMENT STATE message. Reports zero when message is not present.
latitude<br>longitude<br>altitude<br>position_covariance<br>position_covariance_typePOS LLH COVZeros when the fix is invalid. If position is valid altitude is always present (i.e. never NaN). Covariance, if valid, is always TYPE_KNOWN (full matrix).

TwistWithCovarianceStamped

geometry_msgs/msg/TwistWithCovarianceStamped

SBP Messages Used

Topic Publication

Topic publication depends on timestamp_source_gnss setting flag in the configuration file:

Topic Fields

ROS2 Message FieldSBP Message Data SourceNotes
header.stampUTC TIMESee Topic Publication for time stamping details
header.frame_id--Text from frame_name field in the settings.yaml configuration file
linear.x<br>linear.y<br>linear.zVEL NED COVConversion from NED frame:<br>x = east<br>y = north<br>z = -down<br>Zeros when velocity is invalid.
angular.x<br>angular.y<br>angular.z--Not populated. Always zero.
covarianceVEL NED COVIf velocity is valid, linear velocity covariance is full matrix. covariance[0] is set to -1 when linear velocity is invalid. covariance[21] is always -1.

Baseline

swiftnav-ros2/msg/Baseline Proprietary message

SBP Messages Used

Topic Publication

Topic publication depends on timestamp_source_gnss setting flag in the configuration file:

Topic Fields

ROS2 Message FieldSBP Message Data SourceNotes
header.stampUTC TIMESee Topic Publication for time stamping details
header.frame_id--Text from frame_name field in the settings.yaml configuration file
modeBASELINE NEDSolution mode:<br>0 - Invalid<br>3 - Float RTK<br>4 - Fixed RTK
satellites_usedBASELINE NEDNumber of satellites used in the solution
baseline_n_m<br>baseline_e_m<br>baseline_d_mBASELINE NEDBaseline NED vectors in [m]. Zeros when invalid. Vectors origin is at the base location.
baseline_err_h_mBASELINE NEDEstimated (95%) horizontal error of baseline in [m]. Zero when invalid.
baseline_err_v_mBASELINE NEDEstimated (95%) vertical error of baseline in [m]. Zero when invalid.
baseline_length_mBASELINE NEDComputed 3D baseline length. Zero when invalid.
baseline_length_h_mBASELINE NEDComputed horizontal baseline length. Zero when invalid.
baseline_orientation_validBASELINE NEDTrue when baseline orientation (dir and dip) is valid. False when invalid.
baseline_dir_degBASELINE NEDComputed horizontal angle (bearing/heading) from base to rover in [degrees]. Valid only in RTK fixed mode. Range [0..360) from true north. Zero when invalid.
baseline_dir_err_degBASELINE NEDEstimated (95%) error of baseline_dir_deg in [degrees]. Range [0..180]. Zero when invalid.
baseline_dip_degBASELINE NEDComputed vertical angle from base to rover in [degrees]. Valid only in RTK fixed mode. Range [-90..90]. Zero when invalid.
baseline_dip_err_degBASELINE NEDEstimated (95%) error of baseline_dip_deg in [degrees]. Range [0..90]. Zero when invalid.

TimeReference

sensor_msgs/msg/TimeReference

SBP Messages Used

Topic Publication

Topic publication depends on timestamp_source_gnss setting flag in the configuration file:

Topic Fields

ROS2 Message FieldSBP Message Data SourceNotes
header.stampUTC TIMESee Topic Publication for time stamping details
header.frame_id--Not used
time_refGPS TIMEGPS time in seconds since 1980-01-06. sec value is set to -1 if the GPS time is not available.
source--Text from frame_name field in the settings.yaml configuration file

Imu

sensor_msgs/msg/Imu

SBP Messages Used

Topic Publication

Topic is published upon receiving IMU RAW SBP message. Time stamp depends on timestamp_source_gnss setting flag in the configuration file:

Topic Fields

ROS2 Message FieldSBP Message Data SourceNotes
header.stampUTC TIME<br>GPS TIME<br>GNSS TIME OFFSETSee Topic Publication for time stamping details
header.frame_id--Text from frame_name field in the settings.yaml configuration file
orientation<br>orientation_covariance--Not populated. Always zero. orientation_covariance[0] is always -1.
angular_velocityIMU RAW<br>IMU AUXReported in sensor frame. Zeros when invalid.
angular_velocity_covariance--Not populated. angular_velocity_covariance[0] is set to -1 when angular velocity is not valid or when the time stamping source has changed
linear_accelerationIMU RAW<br>IMU AUXReported in sensor frame. Zeros when invalid.
linear_acceleration_covariance--Not populated. linear_acceleration_covariance[0] is set to -1 when linear acceleration is not valid or when the time stamping source has changed

Building Driver

Click here if building driver in a docker

Dependencies:

Step 1 (Install ROS 2 Humble):

Follow instructions to install ROS 2 Humble

Step 2 (Install libspb):

In any directory you wish, clone libsp v4.11.0, init the repo, make the lib and install it

  git clone https://github.com/swift-nav/libsbp.git
  cd libsbp
  git checkout v4.11.0
  cd c
  git submodule update --init --recursive
  mkdir build
  cd build
  cmake DCMAKE_CXX_STANDARD=17 -DCMAKE_CXX_STANDARD_REQUIRED=ON -DCMAKE_CXX_EXTENSIONS=OFF ../ 
  make
  sudo make install

Step 3 (Download Driver Code)

Navigate to workspace directory (e.g.: ~/workspace) and download driver source files

  cd ~/workspace
  mkdir src
  cd src
  git clone https://github.com/swift-nav/swiftnav-ros2.git

Step 4 (Install Dependencies)

Initialize environment and install dependencies

  cd ~/workspace
  source /opt/ros/humble/setup.bash
  sudo apt-get update
  sudo apt-get install libserialport-dev
  rosdep install --from-paths src --ignore-src -r -y

Step 5 (Edit Configuration)

Edit configuration file as required. See ROS 2 driver configuration for setting details.

  nano ~/workspace/src/swiftnav-ros2/config/settings.yaml

Step 6 (Build)

Initialize environment and build the driver

  cd ~/workspace
  source /opt/ros/humble/setup.bash
  colcon build

Launching Driver

Launching

Source installed driver and start it

  source install/setup.bash
  ros2 launch swiftnav_ros2_driver start.py

Driver Launch Example

Viewing Topics

Swift specific SBP messages are not a part of the ROS 2 standard library, therefore the following command must be run in any terminal that is used for interfacing with this driver (e.g.: echoing the baseline message in a new terminal)

  source install/setup.bash
  ros2 topic echo /baseline

Changing Configuration

Changing the configuration file can be done in the driver source (config/settings.yaml), but the driver will need to be rebuilt. Alternatively, the configuration file can be changed in the installed directory:

  nano install/swiftnav_ros2_driver/share/swiftnav_ros2_driver/config/settings.yaml

Driver Configuration

The driver configuration is stored in the config/settings.yaml file. The following settings are available:

ParameterAccepted ValuesDescription
interface1, 2, 3SwiftNav GNSS receiver communication interface:<br>1 - TCP Client<br>2 - Serial port<br>3 - File (playback)
host_ipE.g.: 192.168.0.222IP address of the GNSS receiver. Only used if interface is 1.
host_portE.g.: 55556TCP port used. Only used if interface is 1.
read_timeout<br>write_timeoutE.g.: 10000A timeout for read/write operations in milliseconds. Used for interface 1 and 2.
device_nameE.g.: /dev/ttyS0 (Linux), COM1 (Windows)Serial device name. Only used if interface is 2.
connection_strE.g.: 115200|N|8|1|N (See Connection String Description)A connection string that describes the parameters needed for the serial communication. Only used if interface is 2.
sbp_fileE.g.: /logs/sbp-file.sbpSBP file name for playback. Absolute path is required. Only used if interface is 3. Playback is done at file reading rate, not a real-time.
frame_namestringROS topics frame name
timestamp_source_gnssTrue, FalseTopic publication header time stamp source. True: use GNSS receiver reported time, False: use current platfrom time.
baseline_dir_offset_deg-180.0 .. 180.0RTK Baseline direction offset in [deg]. Floating point value is required.
baseline_dip_offset_deg-90.0 .. 90.0RTK Baseline dip offset in [deg]. Floating point value is required.
track_update_min_speed_mpsE.g.: 1.0Mininal horizontal speed for track updates from SBP message VEL NED COV in [m/s]. track and err_track outputs are 'frozen' below this threshold. Floating point value is required.
enabled_publishers[]gpsfix<br>navsatfix<br>twistwithcovariancestamped<br>baseline<br>timereference<br>imuList of enabled publishers. Delete (comment out) the line to disable publisher.
log_sbp_messagesTrue, FalseEnable/disable SBP raw data recording.
log_sbp_filepathE.g.: /logs/sbp-files/Absolute path (without a file name) for SBP log file location. File name is created automatically with the current date and time, e.g.: swiftnav-20230404-160720.sbp.

Connection String Description

The connection string for the serial interface has the form: BAUD RATE|PARITY|DATA BITS|STOP BITS|FLOW CONTROL

Baud Rates

1200, 2400, 4800, 9600, 19200, 38400, 57600, 115200, 230400, 460800, 921600.

Parity

ValueDescription
NNo parity
EEven parity
OOdd parity
MMark parity (Not available in some Linux distributions)
SSpace parity (Not available in some Linux distributions)

Data Bits

7 or 8

Stop Bits

1 or 2

Flow Control

ValueDescription
NNo flow control
XXon/Xoff
RRTS/CTS
DDTR/DSR

GNSS Receiver Configuration

The ROS 2 driver works with Swift Navigation receivers and Starling Position Engine software using data in SBP protocol. Refer to the receiver-specific manual to configure your receiver:

It's recommended to dedicate one output port for ROS and output on that port only messages required by the driver. This will minimize the latency and jitter of the incoming messages, and decrease CPU load.

The driver uses the following SBP messages:

Message NameMessage ID (decimal)Description
MEASUREMENT STATE97Satellite tracking data
GPS TIME258GPS time
UTC TIME259UTC time
DOPS520Dillution Of Precision
BASELINE NED524Baseline vectors in NED frame
POS LLH COV529Position (latitude, longitude, altitude) with covariance
VEL NED COV530Velocity vectors in NED frame with covariance
ORIENT EULER545Orientation (roll, pitch, yaw)<br>Note: message is available only in products with inertial fusion enabled
IMU RAW2304Raw IMU data
IMU AUX2305IMU temperature and senor ranges
GNSS TIME OFFSET65287Offset of the local time with respect to GNSS time

Download Swift Binary Protocol Specification

Piksi Multi / Duro Configuration Example

Piksi Multi and Duro configuration can be changed using Swift Console program. TCP Server 1 settings example:

Piksi Multi Configuration Example

Note: Click SAVE TO DEVICE button to memorize settings over the power cycle.

Starling Configuration Example

Starling configuration is saved in the yaml configuration file. TCP server output example:

...
  outputs:
    - name: sbp-ros2
      protocol: sbp
      type: tcp-server
      port: 55556
      max-conns: 4
      sbp:
        enabled-messages: [ 97,258,259,520,524,529,530,545,2304,2305,65287 ]
...

Technical Support

Support requests can be made by filling the Support Request Form on the Swift Navigation Support page (Support Request Form button is at the bottom of the page). A simple login is required to confirm your email address.