septentrio_gnss_driver package from septentrio_gnss_driver repo

septentrio_gnss_driver

Package Summary

Tags No category tags.
Version 1.3.2
License BSD 3-Clause License
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/septentrio-gnss/septentrio_gnss_driver.git
VCS Type git
VCS Version ros2
Last Updated 2023-11-22
Dev Status MAINTAINED
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

ROSaic: C++ driver for Septentrio's mosaic receivers and beyond

Additional Links

Maintainers

  • Tibor Dome
  • Septentrio

Authors

  • Tibor Dome

ROSaic = ROS + mosaic

Overview

This repository hosts drivers for ROS (Melodic and Noetic) and ROS 2 (Foxy, Galactic, Humble, Rolling, and beyond) - written in C++ - that work with mosaic and AsteRx - two of Septentrio's cutting-edge GNSS and GNSS/INS receiver families - and beyond. The ROS 2 version is available in this branch, whereas the ROS 1 version is available in the branch master.

Main Features: - Supports Septentrio's single antenna GNSS, dual antenna GNSS and INS receivers - Supports serial, TCP/IP and USB connections, the latter being compatible with both serial (RNDIS) and TCP/IP protocols - Supports several ASCII (including key NMEA ones) messages and SBF (Septentrio Binary Format) blocks - Reports status of AIM+ (Advanced Interference Mitigation including OSNMA) anti-jamming and anti-spoofing. - Can publish nav_msgs/Odometry message for INS receivers - Can blend SBF blocks PVTGeodetic, PosCovGeodetic, ChannelStatus, MeasEpoch, AttEuler, AttCovEuler, VelCovGeodetic and DOP in order to publish gps_common/GPSFix and sensor_msgs/NavSatFix messages - Supports axis convention conversion as Septentrio follows the NED convention, whereas ROS is ENU. - Easy configuration of multiple RTK corrections simultaneously (via NTRIP, TCP/IP stream, or serial) - Can play back PCAP capture logs for testing purposes - Tested with the mosaic-X5, mosaic-H, AsteRx-m3 Pro+ and the AsteRx-SBi3 Pro receiver - Easy to add support for more log types

Please let the maintainers know of your success or failure in using the driver with other devices so we can update this page appropriately.

Dependencies

The ros2 branch for this driver functions on ROS Foxy, Galactic, Rolling, and Humble (Ubuntu 20.04 or 22.04 respectively). It is thus necessary to install the ROS version that has been designed for your Linux distro.

Additional ROS packages have to be installed for the NMEA and GPSFix messages.

sudo apt install ros-$ROS_DISTRO-nmea-msgs ros-$ROS_DISTRO-gps-msgs.

The serial and TCP/IP communication interface of the ROS driver is established by means of the Boost C++ library. In the unlikely event that the below installation instructions fail to install Boost on the fly, please install the Boost libraries via

sudo apt install libboost-all-dev.

Compatiblity with PCAP captures are incorporated through pcap libraries. Install the necessary headers via

sudo apt install libpcap-dev.

Conversions from LLA to UTM are incorporated through GeographicLib. Install the necessary headers via

sudo apt install libgeographic-dev

Usage

Binary Install The binary release is now available for Foxy and Galactic. To install the binary package, simply run `sudo apt-get install ros-$ROS_DISTRO-septentrio-gnss-driver`.
Build from Source The package has to be built from source using [`colcon`](https://docs.ros.org/en/humble/Tutorials/Beginner-Client-Libraries/Colcon-Tutorial.html): ``` source /opt/ros/${ROS_DISTRO}/setup.bash # In case you do not use the default shell of Ubuntu, you need to source another script, e.g. setup.sh. mkdir -p ~/septentrio/src # Note: Change accordingly depending on where you want your package to be installed. cd ~/septentrio/src git clone https://github.com/septentrio-gnss/septentrio_gnss_driver git checkout ros2 # Install mentioned dependencies (`sudo apt install ros-$ROS_DISTRO-nmea_msgs ros-$ROS_DISTRO-gps-msgs libboost-all-dev libpcap-dev libgeographic-dev`) colcon build --packages-up-to septentrio_gnss_driver # Be sure to call colcon build in the root folder of your workspace. Launch files are installed, so changing them on the fly in the source folder only works with installing by symlinks: add `--symlink-install` echo "source ~/septentrio/devel/setup.bash" >> ~/.bashrc # It is convenient if the ROS environment variable is automatically added to your bash session every time a new shell is launched. Again, this works for bash shells only. Also note that if you have more than one ROS distribution installed, ~/.bashrc must only source the setup.bash for the version you are currently using. source ~/.bashrc ``` Run tests ``` colcon test --packages-select septentrio_gnss_driver --event-handlers console_direct+ ```
Notes Before Usage + In your bash sessions, navigating to the ROSaic package can be achieved from anywhere with no more effort than `roscd septentrio_gnss_driver`. + The driver assumes that our anonymous access to the Rx grants us full control rights. This should be the case by default, and can otherwise be changed with the `setDefaultAccessLevel` command. If user control is in place user credentials can be given by parameters `login.user` and `login.password`. + ROSaic only works from C++17 onwards due to std::any() etc. + Note for setting hw_flow_control: This is a string parameter, setting it to off without quotes leads to the fact that it is not read in correctly. + Note for setting ant_(aux1)_serial_nr: This is a string parameter, numeric only serial numbers should be put in quotes. If this is not done a warning will be issued and the driver tries to parse it as integer. + Once the colcon build or binary installation is finished, adapt the `config/rover.yaml` file according to your needs or assemble a new one. Launch as composition with `ros2 launch septentrio_gnss_driver rover.launch.py` to use `rover.yaml` or add `file_name:=xxx.yaml` to use a custom config. Alternatively launch as node with `ros2 launch septentrio_gnss_driver rover_node.launch.py` to use `rover_node.yaml` or add `file_name:=xxx.yaml` to use a custom config. Specify the communication parameters, the ROS messages to be published, the frequency at which the latter should happen etc. + Besides the aforementioned config file `rover.yaml` containing all parameters, specialized launch files for GNSS `config/gnss.yaml` and INS `config/ins.yaml` respectively contain only the relevant parameters in each case. - NOTE: Unless `configure_rx` is set to `false`, this driver will overwrite the previous values of the parameters, even if the value is left to zero in the "yaml" file. + The driver was developed and tested with firmware versions >= 4.10.0 for GNSS and >= 1.3.2 for INS. Receivers with older firmware versions are supported but some features may not be available. Known limitations are: * GNSS with firmware < 4.10.0 does not support IP over USB. * GNSS with firmware < 4.12.1 does not support OSNMA. * INS with firmware < 1.3.2 does not support NTP. * INS with firmware < 1.4 does not support OSNMA. * INS with firmware < 1.4.1 does not support improved VSM handling allowing for unknown variances. * INS with firmware 1.2.0 does not support velocity aiding. * INS with firmware 1.2.0 does not support setting of initial heading. + Known issues: * UDP over USB: Blocks are sent twice on GNSS with firmware <= 4.12.1 and INS with firmware <= 1.4. For GNSS it is fixed in version 4.14 (released on June 15th 2023), for INS it will be fixed in to-be-released 1.4.1 (expected in November 2023). + If `use_ros_axis_orientation` to `true` axis orientations are converted by the driver between NED (Septentrio: yaw = 0 is north, positive clockwise) and ENU (ROS: yaw = 0 is east, positive counterclockwise). There is no conversion when setting this parameter to `false` and the angles will be consistent with the web GUI in this case. :
``` # Example configuration Settings for the Rover Rx device: tcp://192.168.3.1:28784 serial: baudrate: 921600 hw_flow_control: "off" tcp: ip_server: "" port: 0 udp: ip_server: "" port: 0 unicast_ip: "" configure_rx: true login: user: "" password: "" osnma: mode: "off" ntp_server: "" keep_open: true frame_id: gnss imu_frame_id: imu poi_frame_id: base_link vsm_frame_id: vsm aux1_frame_id: aux1 vehicle_frame_id: base_link insert_local_frame: false local_frame_id: odom get_spatial_config_from_tf: true lock_utm_zone: true use_ros_axis_orientation: true receiver_type: gnss datum: Default poi_to_arp: delta_e: 0.0 delta_n: 0.0 delta_u: 0.0 att_offset: heading: 0.0 pitch: 0.0 ant_type: Unknown ant_aux1_type: Unknown ant_serial_nr: Unknown ant_aux1_serial_nr: Unknown leap_seconds: 18 polling_period: pvt: 500 rest: 500 use_gnss_time: false latency_compensation: false rtk_settings: ntrip_1: id: "NTR1" caster: "1.2.3.4" caster_port: 2101 username: "Asterix" password: "password" mountpoint: "mtpt1" version: "v2" tls: true fingerprint: "AA:BB:56:78:90:12: ... 78:90:12:34" rtk_standard: "RTCMv3" send_gga: "auto" keep_open: true ntrip_2: id: "NTR3" caster: "5.6.7.8" caster_port: 2101 username: "Obelix" password: "password" mountpoint: "mtpt2" version: "v2" tls: false fingerprint: "" rtk_standard: "RTCMv2" send_gga: "auto" keep_open: true ip_server_1: id: "IPS3" port: 28785 rtk_standard: "RTCMv2" send_gga: "auto" keep_open: true ip_server_2: id: "IPS5" port: 28786 rtk_standard: "CMRv2" send_gga: "auto" keep_open: true serial_1: port: "COM1" baud_rate: 230400 rtk_standard: "auto" send_gga: "sec1" keep_open: true serial_2: port: "COM2" baud_rate: 230400 rtk_standard: "auto" send_gga: "off" keep_open: true publish: # For both GNSS and INS Rxs navsatfix: false gpsfix: true gpgga: false gprmc: false gpst: false measepoch: false pvtcartesian: false pvtgeodetic: true basevectorcart: false basevectorgeod: false poscovcartesian: false poscovgeodetic: true velcovcartesian: false velcovgeodetic: false atteuler: true attcoveuler: true pose: false twist: false diagnostics: false aimplusstatus: true galauthstatus: false # For GNSS Rx only gpgsa: false gpgsv: false # For INS Rx only insnavcart: false insnavgeod: false extsensormeas: false imusetup: false velsensorsetup: false exteventinsnavcart: false exteventinsnavgeod: false imu: false localization: false tf: false localization_ecef: false tf_ecef: false # INS-Specific Parameters ins_spatial_config: imu_orientation: theta_x: 0.0 theta_y: 0.0 theta_z: 0.0 poi_lever_arm: delta_x: 0.0 delta_y: 0.0 delta_z: 0.0 ant_lever_arm: x: 0.0 y: 0.0 z: 0.0 vsm_lever_arm: vsm_x: 0.0 vsm_y: 0.0 vsm_z: 0.0 ins_initial_heading: auto ins_std_dev_mask: att_std_dev: 5.0 pos_std_dev: 10.0 ins_use_poi: true ins_vsm: source: "twist" config: [true, false, false] variances_by_parameter: true variances: [0.1, 0.0, 0.0] ip_server: id: "IPS2" port: 28787 keep_open: true serial: port: "COM3" baud_rate: 115200 keep_open: true # Logger activate_debug_log: false ``` In order to launch ROSaic, one must specify all `arg` fields of the `rover.py` file which have no associated default values, i.e. for now only the `file_name` field. Hence, the launch command reads `ros2 launch septentrio_gnss_driver rover.py file_name:=rover.yaml`. If multiple port are utilized for RTK corrections and/or VSM, which shall be closed after driver shutdown (`keep_open: false`), make sure to give the driver enough time to gracefully shutdown as closing the ports takes a few seconds. This can be accomplished in the launch files by increasing the timeout of SIGTERM (e.g. `sigterm_timeout = '10',`), see example launch files`rover.py`and `rover_node.py` respectively.

Inertial Navigation System (INS): Basics

  • An Inertial Navigation System (INS) is a device which takes the rotation and acceleration solutions as obtained from its Inertial Measurement Unit (IMU) and combines those with position and velocity information from the GNSS module. Compared to a GNSS system with 7D or 8D (dual-antenna systems) phase space solutions, the combined, Kalman-filtered 9D phase space solution (3 for position, 3 for velocity, 3 for orientation) of an INS is more accurate, more precise and more stable against GNSS outages.
  • The IMU is typically made up of a 3-axis accelerometer, a 3-axis gyroscope and sometimes a 3-axis magnetometer and measures the system's angular rate and acceleration.

    Measure and Compensate for IMU-Antenna Lever Arm

    • The IMU-antenna lever-arm is the relative position between the IMU reference point and the GNSS Antenna Reference Point (ARP), measured in the vehicle frame.
    • In case of AsteRx SBi3, the IMU reference point is clearly marked on the top panel of the receiver. It is important to compensate for the effect of the lever arm, otherwise the receiver may not be able to calculate an accurate INS position.
    • The IMU/antenna position can be changed by specifying the lever arm's x,yand z parameters in the config.yaml file under the ins_spatial_config.ant_lever_arm parameter.

    Screenshot from 2021-08-03 09-23-19 (1)

    Compensate for IMU Orientation + It is important to take into consideration the mounting direction of the IMU in the body frame of the vehicle. For e.g. when the receiver is installed horizontally with the front panel facing the direction of travel, we must compensate for the IMU’s orientation to make sure the IMU reference frame is aligned with the vehicle reference frame. The IMU position and orientation is printed on the top panel, cf. image below. + The IMU's orientation can be changed by specifying the orientation angles theta_x,theta_yand theta_z in the config.yaml file under ins_spatial_config.imu_orientation + The below image illustrates the orientation of the IMU reference frame with the associated IMU orientation for the depicted installation. Note that for use_ros_axis_orientation: true sensor_default is the top left position.

    Capture (1)

  • These Steps should be followed to configure the receiver in INS integration mode:

    • Specify receiver_type: INS
    • Specify the orientation of the IMU sensor with respect to your vehicle, using the ins_spatial_config.imu_orientation parameter.
    • Specify the IMU-antenna lever arm in the vehicle reference frame. This is the vector starting from the IMU reference point to the ARP of the main GNSS antenna. This can be done by means of the ins_spatial_config.ant_lever_arm parameter.
    • Specify ins_spatial_config.vsm_lever_arm if measurements of a velocity sensor is available.
    • Alternatively the lever arms may be specified via tf. Set get_spatial_config_from_tfto true in this case.
    • If the point of interest is neither the IMU nor the ARP of the main GNSS antenna, the vector between the IMU and the point of interest can be provided with the ins_solution/poi_lever_arm parameter.
  • For further more information about Septentrio receivers, visit Septentrio support resources or check out the user manual and reference guide of the AsteRx SBi3 receiver.

ROSaic Parameters

The following is a list of ROSaic parameters found in the config/rover.yaml file. * Parameters Configuring Communication Ports and Processing of GNSS and INS Data

Connectivity Specs

  • device: location of main device connection. This interface will be used for setup communication and VSM data for INS. Incoming data streams of SBF blocks and NMEA sentences are recevied either via this interface or a static IP server for TCP and/or UDP. The former will be utilized if section stream_device.tcp and stream_device.udp are not configured.
    • serial:xxx format for serial connections,where xxx is the device node, e.g. serial:/dev/ttyS0. If using serial over USB, it is recommended to specify the port by ID as the Rx may get a different ttyXXX on reconnection, e.g. serial:/dev/serial/by-id/usb-Septentrio_Septentrio_USB_Device_xyz.
    • file_name:path/to/file.sbf format for publishing from an SBF log
    • file_name:path/to/file.pcap format for publishing from PCAP capture.
      • Regarding the file path, ROS_HOME=`pwd` in front of roslaunch septentrio... might be useful to specify that the node should be started using the executable's directory as its working-directory.
    • tcp://host:port format for TCP/IP connections
      • 28784 should be used as the default (command) port for TCP/IP connections. If another port is specified, the receiver needs to be (re-)configured via the Web Interface before ROSaic can be used.
      • An RNDIS IP interface is provided via USB, assigning the address 192.168.3.1 to the receiver. This should work on most modern Linux distributions. To verify successful connection, open a web browser to access the web interface of the receiver using the IP address 192.168.3.1.
    • default: tcp://192.168.3.1:28784
  • serial: specifications for serial communication
    • baudrate: serial baud rate to be used in a serial connection. Ensure the provided rate is sufficient for the chosen SBF blocks. For example, activating MeasEpoch (also necessary for /gpsfix) may require up to almost 400 kBit/s.
    • rx_serial_port: determines to which (virtual) serial port of the Rx we want to get connected to, e.g. USB1 or COM1
    • hw_flow_control: specifies whether the serial (the Rx's COM ports, not USB1 or USB2) connection to the Rx should have UART hardware flow control enabled or not
      • off to disable UART hardware flow control, RTS|CTS to enable it
    • default: 921600, USB1, off
  • stream_device: If left unconfigured, by default device is utilized for the data streams. Within stream_device static IP servers may be defined instead. In config mode (configure_rx set to true), TCP will be prioritized over UDP. If Rx is pre-configured, both may be set simultaneously.
    • tcp: specifications for static TCP server of SBF blocks and NMEA sentences.
      • ip_server: IP server of Rx to be used, e.g. “IPS1”.
      • port: UDP destination port.
    • udp: specifications for low latency UDP reception of SBF blocks and NMEA sentences.
      • ip_server: IP server of Rx to be used, e.g. “IPS1”.
      • port: UDP destination port.
      • unicast_ip: Set to computer's IP to use unicast (optional). If not set multicast will be used.
  • login: credentials for user authentication to perform actions not allowed to anonymous users. Leave empty for anonymous access.
    • user: user name
    • password: password

OSNMA

  • osnma: Configuration of the Open Service Navigation Message Authentication (OSNMA) feature.
    • mode: Three operating modes are supported: off where OSNMA authentication is disabled, loose where satellites are included in the PVT if they are successfully authenticated or if their authentication status is unknown, and strict where only successfully-authenticated satellites are included in the PVT. In case of strict synchronization via NTP is mandatory.
      • default: off
    • ntp_server: In strict mode, OSNMA authentication requires the availability of external time information. In loose mode, this is optional but recommended for enhanced security. The receiver can connect to an NTP time server for this purpose. Options are default to let the receiver choose an NTP server or specify one like pool.ntp.org for example.
      • default: ""
    • keep_open: Wether OSNMA shall be kept active on driver shutdown.
      • default: true

Receiver Configuration

+ configure_rx: Wether to configure the Rx according to the config file. If set to `false`, the Rx has to be configured via the web interface and the settings must be saved. On the driver side communication has to set accordingly to serial, TCP or UDP (TCP and UDP may even be used simultaneously in this case). For TCP communication it is recommended to use a static TCP server (`stream_device.tcp.ip_server` and `stream_device.tcp.port`), since dynamic connections (`device` is tcp) are not guaranteed to have the same id on reconnection. It should also be ensured that obligatory SBF blocks are activated (as of now: ReceiverTime if `use_gnss_time` is set to `true`; `PVTGeodetic`or `PVTCartesian` if latency compensation for PVT related blocks shall be used). Further, if ROS messages compiled from multiple SBF blocks, it should be ensured that all necessary blocks are activated with matching periods, details can be found in section [ROS Topic Publications](#ros-topic-publications). The messages that shall be published still have to be set to `true` in the *NMEA/SBF Messages to be Published* section. Also, parameters concerning the connection and node setup are still relevant (sections: *Connectivity Specs*, *receiver type*, *Frame IDs*, *UTM Zone Locking*, *Time Systems*, *Logger*).
  + default: true

Receiver Type

  • receiver_type: This parameter is to select the type of the Septentrio receiver
    • gnss for GNSS receivers.
    • ins for INS receivers.
    • default: gnss
  • multi_antenna: Whether or not the Rx has multiple antennas.
    • default: false

Frame IDs

  • frame_id: name of the ROS tf frame for the Rx, placed in the header of published GNSS messages. It corresponds to the frame of the main antenna.
    • In ROS, the tf package lets you keep track of multiple coordinate frames over time. The frame ID will be resolved by tf_prefix if defined. If a ROS message has a header (all of those we publish do), the frame ID can be found via rostopic echo /topic, where /topic is the topic into which the message is being published.
    • default: gnss
  • imu_frame_id: name of the ROS tf frame for the IMU, placed in the header of published IMU message
    • default: imu
  • poi_frame_id: name of the ROS tf frame for the POI, placed in the child frame_id of localization if ins_use_poi is set to true.
    • default: base_link
  • vsm_frame_id: name of the ROS tf frame for the velocity sensor.
    • default: vsm
  • aux1_frame_id: name of the ROS tf frame for the aux1 antenna.
    • default: aux1
  • vehicle_frame_id: name of the ROS tf frame for the vehicle. Default is the same as poi_frame_id but may be set otherwise.
    • default: base_link
  • local_frame_id: name of the ROS tf frame for the local frame.
    • default: odom
  • insert_local_frame: Wether to insert a local frame to published tf according to ROS REP 105. The transform from the local frame specified by local_frame_id to the vehicle frame specified by vehicle_frame_id has to be provided, e.g. by odometry. Insertion of the local frame means the transform between local frame and global frame is published instead of transform between vehicle frame and global frame.
    • default: false
  • get_spatial_config_from_tf: wether to get the spatial config via tf with the above mentioned frame ids. This will override spatial settings of the config file. For receiver type ins with multi_antenna set to true all frames have to be provided, with multi_antenna set to false, aux1_frame_id is not necessary. For type gnss with dual-antenna setup only frame_id, aux1_frame_id, and poi_frame_id are needed. For single-antenna gnss no frames are needed. Keep in mind that tf has a tree structure. Thus, poi_frame_id is the base for all mentioned frames.
    • default: false
  • use_ros_axis_orientation Wether to use ROS axis orientations according to ROS REP 103 for body related frames and geographic frames. Body frame directions affect INS lever arms and IMU orientation setup parameters. Geographic frame directions affect orientation Euler angles for INS+GNSS and attitude of dual-antenna GNSS. If use_ros_axis_orientation is set to true, the driver converts between the NED convention (Septentrio: yaw = 0 is north, positive clockwise), and ENU convention (ROS: yaw = 0 is east, positive counterclockwise). There is no conversion when setting this parameter to false and the angles will be consistent with the web GUI in this case.
    • If set to false Septentrios definition is used, i.e., front-right-down body related frames and NED (north-east-down) for orientation frames.
    • If set to true ROS definition is used, i.e., front-left-up body related frames and ENU (east-north-up) for orientation frames.
    • default: true

UTM zone locking + lock_utm_zone: wether the UTM zone of the initial localization is locked, i.e., this zone is kept even if a zone transition would occur. + default: true

Datum

  • datum: With this command, the datum the coordinates should refer to is selected. With setting it to Default, the datum depends on the positioning mode, e.g. WGS84 for standalone positioning.
    • Since the standardized GGA message does only provide the orthometric height (= MSL height = distance from Earth's surface to geoid) and the geoid undulation (distance from geoid to ellipsoid) for which non-WGS84 datums cannot be specified, it does not affect the GGA message.
    • default: Default

POI-ARP Offset

+ `poi_to_arp`: offsets of the main GNSS antenna reference point (ARP) with respect to the point of interest (POI = marker). Use for static receivers only.
+ The parameters `delta_e`, `delta_n` and `delta_u` are the offsets in the East, North and Up (ENU) directions respectively, expressed in meters.
+ All absolute positions reported by the receiver are POI positions, obtained by subtracting this offset from the ARP. The purpose is to take into account the fact that the antenna may not be located directly on the surveying POI.
+ default: `0.0`, `0.0` and `0.0`

Antenna Attitude Offset

+ `att_offset`: Angular offset between two antennas (Main and Aux) and vehicle frame
+ `heading`: The perpendicular (azimuth) axis can be compensated for by adjusting the `heading` parameter
+ `pitch`: Vertical (elevation) offset can be compensated for by adjusting the `pitch` parameter
+ default: `0.0`, `0.0` (degrees)

Antenna Specs

  • ant_type: type of your main GNSS antenna
    • For best positional accuracy, it is recommended to select a type from the list returned by the command lstAntennaInfo, Overview. This is the list of antennas for which the receiver can compensate for phase center variation.
    • By default and if ant_type does not match any entry in the list returned by lstAntennaInfo, Overview, the receiver will assume that the phase center variation is zero at all elevations and frequency bands, and the position will not be as accurate.
    • default: Unknown
  • ant_serial_nr: serial number of your main GNSS antenna
  • ant_aux1_type and ant_aux1_serial_nr: same for Aux1 antenna

Leap Seconds

  • leap_seconds: Leap seconds are automatically gathered from the receiver via the SBF block ReceiverTime. If a log file is used for simulation and this block was not recorded, the number of leap seconds that have been inserted up until the point of ROSaic usage can be set by this parameter.
    • At the time of writing the code (2020), the GPS time, which is unaffected by leap seconds, was ahead of UTC time by 18 leap seconds. Adapt the leap_seconds parameter accordingly as soon as the next leap second is inserted into the UTC time or in case you are using ROSaic for the purpose of simulations.

Polling Periods

  • polling_period.pvt: desired period in milliseconds between the polling of two consecutive PVTGeodetic, PosCovGeodetic, PVTCartesian and PosCovCartesian blocks and - if published - between the publishing of two of the corresponding ROS messages (e.g. septentrio_gnss_driver/PVTGeodetic.msg). Consult firmware manual for allowed periods. If the period is set to a lower value than the receiver is capable of, it will be published with the next higher period. If set to 0, the SBF blocks are output at their natural renewal rate (OnChange).
  • polling_period.rest: desired period in milliseconds between the polling of all other SBF blocks and NMEA sentences not addressed by the previous parameter, and - if published - between the publishing of all other ROS messages
    • default: 500 (2 Hz)

Time Systems

  • use_gnss_time: true if the ROS message headers' unix epoch time field shall be constructed from the TOW/WNC (in the SBF case) and UTC (in the NMEA case) data, false if those times shall be taken by the driver from ROS time. If use_gnss_time is set to true, make sure the ROS system is synchronized to an NTP time server either via internet or ideally via the Septentrio receiver since the latter serves as a Stratum 1 time server not dependent on an internet connection. The NTP server of the receiver is automatically activated on the Septentrio receiver (for INS/GNSS a firmware >= 1.3.3 is needed).
    • default: true
  • latency_compensation: Rx reports processing latency in PVT and INS blocks. If set to truethis latency is subtracted from ROS timestamps in related blocks (i.e., use_gnss_time set to false). Related blocks are INS, PVT, Covariances, and BaseVectors. In case of use_gnss_time set to true, the latency is already compensated within the RX and included in the reported timestamps.
    • default: false

RTK corrections

  • rtk_settings: determines RTK connection parameters
    • There are multiple possibilities to feed RTK corrections to the Rx. They may be set simultaneously and the Rx will choose the nearest source.
      • a) ntrip_# if the Rx has internet access and is able to receieve NTRIP streams from a caster. Up to three NTRIP connections are possible.
      • b) ip_server_# if corrections are to be receieved via TCP/IP for example over Data Link from Septentrio's RxTools is installed on a computer. Up to five IP server connections are possible.
      • c) serial_# if corrections are to be receieved via a serial port for example over radio link from a local RTK base or over Data Link from Septentrio's RxTools installed on a computer. Up to five serial connections are possible.
    • ntrip_#: for receiving corretions from an NTRIP caster (# is from 1 ... 3).
      • id: NTRIP connection NTR1, NTR2, or NTR3.
      • default: ""
      • caster: is the hostname or IP address of the NTRIP caster to connect to.
      • default: ""
      • caster_port: IP port of the NTRIP caster.
      • default: 2021
      • username: user name for the NTRIP caster.
      • default: ""
      • pasword: password for the NTRIP caster. The receiver encrypts the password so that it cannot be read back with the command "getNtripSettings".
      • default: ""
      • mountpoint: mount point of the NTRP caster to be used.
      • default: ""
      • version: argument specifies which version of the NTRIP protocol to use (v1 or v2).
      • default: "v2"
      • tls: determines wether to use TLS.
      • default: false
      • fingerprint: fingerprint to be used if the certificate is self-signed. If the caster’s certificate is known by a publicly-trusted certification authority, fingerprint should be left empty.
      • default: ""
      • rtk_standard: determines the RTK standard, options are auto, RTCMv2, RTCMv3, or CMRv2.
      • default: "auto"
      • send_gga: specifies whether or not to send NMEA GGA messages to the NTRIP caster, and at which rate. It must be one of auto, off, sec1, sec5, sec10 or sec60. In auto mode, the receiver automatically sends GGA messages if requested by the caster.
      • default: "auto"
      • keep_open: determines wether this connection shall be kept open. If set to true the Rx will still be able to receive RTK corrections to improve precision after driver is shut down.
      • default: true
    • ip_server_#: for receiving corretions via TCP/IP (# is from 1 ... 5).
      • id: specifies the IP server IPS1, IPS2, IPS3, IPS4, or IPS5. Note that ROSaic will send GGA messages on this connection if send_gga is set, such that in the Data Link application of RxTools one just needs to set up a TCP client to the host name as found in the ROSaic parameter device with the port as found in port. If the latter connection were connection 1 on Data Link, then connection 2 would set up an NTRIP client connecting to the NTRIP caster as specified in the above parameters in order to forward the corrections from connection 2 to connection 1.
      • default: ""
      • port: its port number of the connection that ROSaic establishes on the receiver. When selecting a port number, make sure to avoid conflicts with other services.
      • default: 0
      • rtk_standard: determines the RTK standard, options are auto, RTCMv2, RTCMv3, or CMRv2.
      • default: ""
      • send_gga: specifies whether or not to send NMEA GGA messages to the NTRIP caster, and at which rate. It must be one of auto, off, sec1, sec5, sec10 or sec60. In auto mode, the receiver sends with sec1.
      • default: "auto"
      • keep_open: determines wether this connection shall be kept open. If set to true the Rx will still be able to receive RTK corrections to improve precision after driver is shut down.
      • default: true
    • serial_#: for receiving corretions via serial connection (# is from 1 ... 5).
      • port: Serial connection COM1, COM2, COM3, USB1, or USB2 on which corrections could be forwarded to the Rx from a serially connected radio link modem or via Data Link for example.
      • default: ""
      • baud_rate: sets the baud rate of this port for genuine serial ports, i.e., not relevant for USB connection.
      • default: 115200
      • rtk_standard: determines the RTK standard, options are auto, RTCMv2, RTCMv3, or CMRv2.
      • default: "auto"
      • send_gga: specifies whether or not to send NMEA GGA messages to the NTRIP caster, and at which rate. It must be one of auto, off, sec1, sec5, sec10 or sec60. In auto mode, the receiver sends with sec1.
      • default: "auto"
      • keep_open: determines wether this connection shall be kept open. If set to true the Rx will still be able to receive RTK corrections to improve precision after driver is shut down.
      • default: true

INS Specs

+ `ins_spatial_config`: Spatial configuration of INS/IMU. Coordinates according to vehicle related frame directions chosen by `use_ros_axis_orientation` (front-left-up if `true` and front-right-down if `false`).
  + `imu_orientation`: IMU sensor orientation
    + Parameters `theta_x`, `theta_y` and `theta_z` are used to determine the sensor orientation with respect to the vehicle frame. Positive angles correspond to a right-handed (clockwise) rotation of the IMU with respect to its nominal orientation (see below). The order of the rotations is as follows: `theta_z` first, then `theta_y`, then `theta_x`.
    + The nominal orientation is where the IMU is upside down and with the `X axis` marked on the receiver pointing to the front of the vehicle. By contrast, for `use_ros_axis_orientation: true`, nominal orientation is where the `Z axis` of the IMU is pointing upwards and also with the `X axis` marked on the receiver pointing to the front of the vehicle.
    + default: `0.0`, `0.0`, `0.0` (degrees)
  + `poi_lever_arm`: The lever arm from the IMU reference point to a user-defined POI
    + Parameters `delta_x`,`delta_y` and `delta_z` refer to the vehicle reference frame
    + default: `0.0`, `0.0`, `0.0` (meters)
  + `ant_lever_arm`: The lever arm from the IMU reference point to the main GNSS antenna
    + The parameters `x`,`y` and `z` refer to the vehicle reference frame
    + default: `0.0`, `0.0`, `0.0` (meters)
  + `vsm_lever_arm`: The lever arm from the IMU reference point to the velocity sensor
    + The parameters `vsm_x`,`vsm_y` and `vsm_z` refer to the vehicle reference frame 
    + default: `0.0`, `0.0`, `0.0` (meters)
+ `ins_initial_heading`: How the receiver obtains the initial INS/GNSS integrated heading during the alignment phase
    + In case it is `auto`, the initial integrated heading is determined from GNSS measurements.
    + In case it is `stored`, the last known heading when the vehicle stopped before switching off the receiver is used as initial heading. Use if vehicle does not move when the receiver is switched off.
    + default: `auto`
+ `ins_std_dev_mask`: Maximum accepted error
  + `att_std_dev`: Configures an output limit on standard deviation of the attitude angles (max error accepted: 5 degrees)
  + `pos_std_dev`: Configures an output limit on standard deviation of the position (max error accepted: 100 meters)
  + default: `5` degrees, `10` meters    
+ `ins_use_poi`: Whether or not to use the POI defined in `ins_spatial_config.poi_lever_arm`
  + If true, the point at which the INS navigation solution (e.g. in `insnavgeod` ROS topic) is calculated will be the POI as defined above (`poi_frame_id`), otherwise it'll be the main GNSS antenna (`frame_id`). Has to be set to `true` if tf shall be published.
  + default: `true`
+ `ins_vsm`: Configuration of the velocity sensor measurements.
  + `ros`: VSM info received from ROS msgs
    + `source`: Specifies which ROS message type shall be used, options are `odometry` or `twist`. Accordingly, a subscriber is established of the type [`nav_msgs/Odometry.msg`](https://docs.ros2.org/foxy/api/nav_msgs/msg/Odometry.html) or [`geometry_msgs/TwistWithCovarianceStamped.msg`](https://docs.ros2.org/foxy/api/geometry_msgs/msg/TwistWithCovarianceStamped.html) listening on the topics `odometry_vsm` or `twist_vsm` respectively. Only linear velocities are evaluated. Measurements have to be with respect to the frame aligned with the vehicle and defined by `ins_spatial_config.vsm_lever_arm` or tf-frame `vsm_frame_id`, see also comment in [`nav_msgs/Odometry.msg`](https://docs.ros2.org/foxy/api/nav_msgs/msg/Odometry.html) that twist should be specified in `child_frame_id`.
      + default: ""
    + `config`: Defines which measurements belonging to the respective axes are forwarded to the INS. In addition, non-holonomic constraints may be introduced for directions known to be restricted in movement. For example, a vehicle with Ackermann steering is limited in its sidewards and upwards movement. So, even if only motion in x-direction may be measured, zero-velocities for y and z may be sent. Only has to be set if `ins_vsm.ros.source`is set to `odometry` or `twist`.
      + default: []
    + `variances_by_parameter`: Wether variances shall be entered by parameter `ins_vsm.ros.variances` or the values from inside the ROS messages are used. Only has to be set if `ins_vsm.source`is set to `odometry` or `twist`.
      + default: false
    + `variances`: Variances of the respective axes. Only have to be set if `ins_vsm.variances_by_parameter` is set to `true`. Values must be > 0.0, else measurements cannot not be used.
      + default: []
  + `ip_server`:
    + `id`: IP server to receive the VSM info (e.g. `IPS2`).
        + default: ""
    + `port`: TCP port to receive the VSM info. When selecting a port number, make sure to avoid conflicts with other services.
      + default: 0
    + `keep_open` determines wether this connections to receive VSM shall be kept open on driver shutdown. If set to `true` the Rx will still be able to use external VSM info to improve its localization.
      + default: `true`
  + `serial`:
    + `port`: Serial port to receive the VSM info.
      + default: ""
    + `baud_rate`: Baud rate of the serial port to receive the VSM info.
      + default: 115200
    + `keep_open` determines wether this connections to receive VSM shall be kept open on driver shutdown. If set to `true` the Rx will still be able to use external VSM info to improve its localization.
      + default: `true`

Logger

+ `activate_debug_log`: `true` if ROS logger level shall be set to debug.

  • Parameters Configuring (Non-)Publishing of ROS Messages

    NMEA/SBF Messages to be Published

    • publish.gpgga: true to publish nmea_msgs/GPGGA.msg messages into the topic /gpgga
    • publish.gprmc: true to publish nmea_msgs/GPRMC.msg messages into the topic /gprmc
    • publish.gpgsa: true to publish nmea_msgs/GPGSA.msg messages into the topic /gpgsa
    • publish.gpgsv: true to publish nmea_msgs/GPGSV.msg messages into the topic /gpgsv
    • publish.measepoch: true to publish septentrio_gnss_driver/MeasEpoch.msg messages into the topic /measepoch
    • publish.galauthstatus: true to publish septentrio_gnss_driver/GALAuthStatus.msg messages into the topic /galauthstatus and corresponding /diganostics
    • publish.aimplusstatus: true to publish septentrio_gnss_driver/RFStatus.msg messages into the topic /rfstatus, septentrio_gnss_driver/AIMPlusStatus.msg messages into /aimplusstatus and corresponding /diganostics. Some information is only available with active OSNMA.
    • publish.pvtcartesian: true to publish septentrio_gnss_driver/PVTCartesian.msg messages into the topic /pvtcartesian
    • publish.pvtgeodetic: true to publish septentrio_gnss_driver/PVTGeodetic.msg messages into the topic /pvtgeodetic
    • publish.basevectorcart: true to publish septentrio_gnss_driver/BaseVectorCart.msg messages into the topic /basevectorcart
    • publish.basevectorgeod: true to publish septentrio_gnss_driver/BaseVectorGeod.msg messages into the topic /basevectorgeod
    • publish.poscovcartesian: true to publish septentrio_gnss_driver/PosCovCartesian.msg messages into the topic /poscovcartesian
    • publish.poscovgeodetic: true to publish septentrio_gnss_driver/PosCovGeodetic.msg messages into the topic /poscovgeodetic
    • publish.velcovcartesian: true to publish septentrio_gnss_driver/VelCovCartesian.msg messages into the topic /velcovcartesian
    • publish.velcovgeodetic: true to publish septentrio_gnss_driver/VelCovGeodetic.msg messages into the topic /velcovgeodetic
    • publish.atteuler: true to publish septentrio_gnss_driver/AttEuler.msg messages into the topic /atteuler
    • publish.attcoveuler: true to publish septentrio_gnss_driver/AttCovEuler.msg messages into the topic /attcoveuler
    • publish.gpst: true to publish sensor_msgs/TimeReference.msg messages into the topic /gpst
    • publish.navsatfix: true to publish sensor_msgs/NavSatFix.msg messages into the topic /navsatfix
    • publish.gpsfix: true to publish gps_msgs/GPSFix.msg messages into the topic /gpsfix
    • publish.pose: true to publish geometry_msgs/PoseWithCovarianceStamped.msg messages into the topic /pose
    • publish.twist: true to publish geometry_msgs/TwistWithCovarianceStamped.msg messages into the topics /twist and /twist_ins respectively
    • publish.diagnostics: true to publish diagnostic_msgs/DiagnosticArray.msg messages into the topic /diagnostics
    • publish.insnavcart: true to publish septentrio_gnss_driver/INSNavCart.msg message into the topic/insnavcart
    • publish.insnavgeod: true to publish septentrio_gnss_driver/INSNavGeod.msg message into the topic/insnavgeod
    • publish.extsensormeas: true to publish septentrio_gnss_driver/ExtSensorMeas.msg message into the topic/extsensormeas
    • publish.imusetup: true to publish septentrio_gnss_driver/IMUSetup.msg message into the topic/imusetup
    • publish.velsensorsetup: true to publish septentrio_gnss_driver/VelSensorSetup.msgs message into the topic/velsensorsetup
    • publish.exteventinsnavcart: true to publish septentrio_gnss_driver/ExtEventINSNavCart.msgs message into the topic/exteventinsnavcart
    • publish.exteventinsnavgeod: true to publish septentrio_gnss_driver/ExtEventINSNavGeod.msgs message into the topic/exteventinsnavgeod
    • publish.imu: true to publish sensor_msgs/Imu.msg message into the topic/imu
    • publish.localization: true to publish nav_msgs/Odometry.msg message into the topic/localization
    • publish.tf: true to broadcast tf of localization. ins_use_poi must also be set to true to publish tf. Note that only one of publish.tf or publish.tf_ecef may be true.
    • publish.localization_ecef: true to publish nav_msgs/Odometry.msg message into the topic/localization related to ECEF frame.
    • publish.tf_ecef: true to broadcast tf of localization related to ECEF frame. ins_use_poi must also be set to true to publish tf. Note that only one of publish.tf or publish.tf_ecef may be true.

ROS Topic Publications

A selection of NMEA sentences, the majority being standardized sentences, and proprietary SBF blocks is translated into ROS messages, partly generic and partly custom, and can be published at the discretion of the user into the following ROS topics. All published ROS messages, even custom ones, start with a ROS generic header std_msgs/Header.msg, which includes the receiver time stamp as well as the frame ID, the latter being specified in the ROS parameter frame_id.

Available ROS Topics

  • /gpgga: publishes nmea_msgs/Gpgga.msg - converted from the NMEA sentence GGA.
  • /gprmc: publishes nmea_msgs/Gprmc.msg - converted from the NMEA sentence RMC.
  • /gpgsa: publishes nmea_msgs/Gpgsa.msg - converted from the NMEA sentence GSA.
  • /gpgsv: publishes nmea_msgs/Gpgsv.msg - converted from the NMEA sentence GSV.
  • /measepoch: publishes custom ROS message septentrio_gnss_driver/MeasEpoch.msg, corresponding to the SBF block MeasEpoch.
  • /galauthstatus: publishes custom ROS message septentrio_gnss_driver/GALAuthStatus.msg, corresponding to the SBF block GALAuthStatus.
  • /rfstatus: publishes custom ROS message septentrio_gnss_driver/RFStatus.msg, compiled from the SBF block RFStatus.
  • /aimplusstatus: publishes custom ROS message septentrio_gnss_driver/AIMPlusStatus.msg, reporting status of AIM+. Converted from SBF blocks RFStatus and optionally GALAuthStatus. For the latter OSNMA has to be activated.
  • /pvtcartesian: publishes custom ROS message septentrio_gnss_driver/PVTCartesian.msg, corresponding to the SBF block PVTCartesian (GNSS case) or INSNavGeod (INS case).
  • /pvtgeodetic: publishes custom ROS message septentrio_gnss_driver/PVTGeodetic.msg, corresponding to the SBF block PVTGeodetic (GNSS case) or INSNavGeod (INS case).
  • /basevectorcart: publishes custom ROS message septentrio_gnss_driver/BaseVectorCart.msg, corresponding to the SBF block BaseVectorCart.
  • /basevectorgeod: publishes custom ROS message septentrio_gnss_driver/BaseVectorGeod.msg, corresponding to the SBF block BaseVectorGeod.
  • /poscovcartesian: publishes custom ROS message septentrio_gnss_driver/PosCovCartesian.msg, corresponding to SBF block PosCovCartesian (GNSS case) or INSNavGeod (INS case).
  • /poscovgeodetic: publishes custom ROS message septentrio_gnss_driver/PosCovGeodetic.msg, corresponding to SBF block PosCovGeodetic (GNSS case) or INSNavGeod (INS case).
  • /velcovcartesian: publishes custom ROS message septentrio_gnss_driver/VelCovCartesian.msg, corresponding to SBF block VelCovCartesian (GNSS case).
  • /velcovgeodetic: publishes custom ROS message septentrio_gnss_driver/VelCovGeodetic.msg, corresponding to SBF block VelCovGeodetic (GNSS case).
  • /atteuler: publishes custom ROS message septentrio_gnss_driver/AttEuler.msg, corresponding to SBF block AttEuler.
  • /attcoveuler: publishes custom ROS message septentrio_gnss_driver/AttCovEuler.msg, corresponding to the SBF block AttCovEuler.
  • /gpst (for GPS Time): publishes generic ROS message sensor_msgs/TimeReference.msg, converted from the PVTGeodetic (GNSS case) or INSNavGeod (INS case) block's GPS time information, stored in its block header.
  • /navsatfix: publishes generic ROS message sensor_msgs/NavSatFix.msg, converted from the SBF blocks PVTGeodetic,PosCovGeodetic (GNSS case) or INSNavGeod (INS case)
  • /gpsfix: publishes generic ROS message gps_msgs/GPSFix.msg, which is much more detailed than sensor_msgs/NavSatFix.msg, converted from the SBF blocks PVTGeodetic, PosCovGeodetic, ChannelStatus, MeasEpoch, AttEuler, AttCovEuler, VelCovGeodetic, DOP (GNSS case) or INSNavGeod, DOP (INS case). In order to publish heading information, the field dip is diverted from its intended meaning an populated with the heading angle and err_dip with its uncertainty.
  • /pose: publishes generic ROS message geometry_msgs/PoseWithCovarianceStamped.msg, converted from the SBF blocks PVTGeodetic, PosCovGeodetic, AttEuler, AttCovEuler (GNSS case) or INSNavGeod (INS case).
    • Note that GNSS provides absolute positioning, while robots are often localized within a local level cartesian frame. The pose field of this ROS message contains position with respect to the absolute ENU frame (longitude, latitude, height), i.e. not a cartesian frame, while the orientation is with respect to a vehicle-fixed (e.g. for mosaic-x5 in moving base mode via the command setAttitudeOffset, ...) !local! NED frame or ENU frame if use_ros_axis_directions is set true. Thus the orientation is !not! given with respect to the same frame as the position is given in. The cross-covariances are hence set to 0.
  • /twist: publishes generic ROS message geometry_msgs/TwistWithCovarianceStamped.msg, converted from the SBF blocks PVTGeodetic and VelCovGeodetic.
  • /twist_ins: publishes generic ROS message geometry_msgs/TwistWithCovarianceStamped.msg, converted from SBF block INSNavGeod.
  • /insnavcart: publishes custom ROS message septentrio_gnss_driver/INSNavCart.msg, corresponding to SBF block INSNavCart
  • /insnavgeod: publishes custom ROS message septentrio_gnss_driver/INSNavGeod.msg, corresponding to SBF block INSNavGeod
  • /extsensormeas: publishes custom ROS message septentrio_gnss_driver/ExtSensorMeas.msg, corresponding to SBF block ExtSensorMeas.
  • /imusetup: publishes custom ROS message septentrio_gnss_driver/IMUSetup.msg, corresponding to SBF block IMUSetup.
  • /velsensorsetup: publishes custom ROS message septentrio_gnss_driver/VelSensorSetup.msg corresponding to SBF block VelSensorSetup.
  • /exteventinsnavcart: publishes custom ROS message septentrio_gnss_driver/INSNavCart.msg, corresponding to SBF block ExtEventINSNavCart.
  • /exteventinsnavgeod: publishes custom ROS message septentrio_gnss_driver/INSNavGeod.msg, corresponding to SBF block ExtEventINSNavGeod.
  • /diagnostics: accepts generic ROS message diagnostic_msgs/DiagnosticArray.msg, converted from the SBF blocks QualityInd, ReceiverStatus and ReceiverSetup
  • /imu: accepts generic ROS message sensor_msgs/Imu.msg, converted from the SBF blocks ExtSensorMeas and INSNavGeod.
    • The ROS message sensor_msgs/Imu.msg can be fed directly into the robot_localization of the ROS navigation stack. Note that use_ros_axis_orientation should be set to true to adhere to the ENU convention.
  • /localization: accepts generic ROS message nav_msgs/Odometry.msg, converted from the SBF block INSNavGeod and transformed to UTM.
    • The ROS message nav_msgs/Odometry.msg can be fed directly into the robot_localization of the ROS navigation stack. Note that use_ros_axis_orientation should be set to true to adhere to the ENU convention.
  • /localization_ecef: accepts generic ROS message nav_msgs/Odometry.msg, converted from the SBF blocks INSNavCart and INSNavGeod.
    • The ROS message nav_msgs/Odometry.msg can be fed directly into the robot_localization of the ROS navigation stack. Note that use_ros_axis_orientation should be set to true to adhere to the ENU convention.

Suggestions for Improvements

Some Ideas + Equip ROSaic with an NTRIP client such that it can forward corrections to the receiver independently of `Data Link`.

Adding New SBF Blocks or NMEA Sentences

Steps to Follow Is there an SBF or NMEA message that is not being addressed while being important to your application? If yes, follow these steps: 1. Find the log reference of interest in the publicly accessible, official documentation. Hence select the reference guide file, e.g. for mosaic-x5 in the [product support section for mosaic-X5](https://www.septentrio.com/en/support/mosaic/mosaic-x5), Chapter 4, of Septentrio's homepage. 2. SBF: Add a new `.msg` file to the `../msg` folder. And modify the `../CMakeLists.txt` file by adding a new entry to the `add_message_files` section. 3. Add msg header and typedef to `typedefs.hpp`. 4. Parsers: - SBF: Add a parser to the `sbf_blocks.hpp` file. - NMEA: Construct two new parsing files such as `gpgga.cpp` to the `../src/septentrio_gnss_driver/parsers/nmea_parsers` folder and one such as `gpgga.hpp` to the `../include/septentrio_gnss_driver/parsers/nmea_parsers` folder. 5. Processing the message/block: - SBF: Extend the `SbfId` enumeration in the `message_handler.hpp` file with a new entry. - SBF: Extend the SBF switch-case in `message_handler.cpp` file with a new case. - NMEA: Extend the `nmeaMap_` in the `message_handler.hpp` file with a new pair. - NMEA: Extend the NMEA switch-case in `message_handler.cpp` file with a new case. 6. Create a new `publish/..` ROSaic parameter in the `../config/rover.yaml` file and create a boolean variable `publish_xxx` in the struct in the `settings.h` file. Parse the parameter in the `rosaic_node.cpp` file. 7. Add SBF block or NMEA to data stream setup in `communication_core.cpp` (function `configureRx()`).
CHANGELOG

Changelog for package septentrio_gnss_driver

1.3.2 (2022-11-19) -----------* Merge pull request #106 from thomasemter/dev/next2 Fix IMU units * Fix topics namespace * Fix units of imu angular rates * Merge pull request #96 from septentrio-gnss/dev2 Dev2 * Contributors: Thomas Emter, Tibor Dome, septentrio-users

1.3.1 (2022-07-06)

  • New Features

    : - Recovery from connection interruption - Add option to bypass configuration of Rx - Add tests - OSNMA - Latency compensation for ROS timestamps - Output of SBf block VelCovCartesian - Support for UDP and TCP via IP server - New VSM handling allows for unknown variances (INS firmware >= 1.4.1) - Add heading angle to GPSFix msg (by diverting dip field, cf. readme)

  • Improvements

    : - Rework IO core and message handling - Unified stream processing - Internal data queue - Prevent message loss in file reading - Add some explanatory warnings for parameter mismatches - Add units to message definitions

  • Fixes

    : - navsatfix for INS - Empty headers - Single antenna receiver setup

  • Preliminary Features

    : - Output of localization and tf in ECEF frame, testing and feedback welcome

  • Commits

    : - Merge pull request #83 from thomasemter/dev/next2 Update readme - Add expected release dates - Add known issues to readme - Update version - Update readme - Merge pull request #82 from thomasemter/dev/next2 Fix spelling - Categorize stream params - Add keep alive check for TCP - Fix spelling - Add TCP communication via static IP server - Add units to msgs - Fix spelling - Merge pull request #76 from thomasemter/dev/next2 upcoming release - Add heading to GPSFix msg - Move constant - Change log level of firmware check - Add improved VSM handling - Change INS in GNSS node detection to auto - Fix invald v_x var case - Refine readme on UDP - Improve server duplicate check - Add more info un UDP configuration - Fix publish check - Add more publishing checks for configured Rx - Add const for max udp packet size - Update readme and changelog - Add device check to node - Fix param name separators - Add checks for IP server duplicates - Add latency compensation to att msgs - Add device check logic - Add UDP params and setup logic - Fix multi msg per packet - Fix localization stamp and tf publishing - Change VSM to be averaged and published with 2 Hz - Change VSM to be averaged and published with 2 Hz - Always publish raw IMU data as indicated - Change to empty fields - Refine diagnostics naming scheme and add trigger to ensure emission of ReceiverSetup - Change diagnostics naming scheme - Add missing new params to gnss.yaml - Expand readme on AIM+ - Reformulate readme about ROS and ROS2 - Add custom message to report AIM+ status - Catch invalid UTM conversion - Robustify command reset - Add RFStatus diagnostics - Add VelCovCartesian output - Refine Rx type check - Add option for latency compensation - Fix param type misinterpretation - Add OSNMA msg and diagnostics - Update changelog - Refine README and fix compiled message logic - Update changelog - Add warning for configuring INS as GNSS - Add warn log for misconfiguration - Fix pose publishing rate - Fix navsatfix publishing - Make vars const - Merge rework of internal IO handling - Change connection thread - Fix attitude cov flipped twice - Add cov alignment from true north to grid north - Rename meridian convergence and fix sense - Remove obsolete define - Add tests - Rename example launch files so they are found by auto-completion - Merge branch \'dev/ros2\' into dev/next2 - Fix lat/long in rad - Fix readme concerning ROS 2 distros - Reorder localization msg filling - Update readme - Fix NED to ECEF rotation matrix - Add localization ECEF publishing - Add ecef localization msg - Add local to ecef transforms - Contributors: Thomas Emter, Tibor Dome

1.2.3 (2022-11-09)

  • New Features

    : - Twist output option - Example config files for GNSS and INS - Get leap seconds from receiver - Firmware check - VSM from odometry or twist ROS messages - Add receiver type in case INS is used in GNSS mode - Add publishing of base vector topics

  • Improvements

    : - Rework RTK corrections parameters and improve flexibility

  • Fixes

    : - /tf not being published without /localization - Twist covariance matrix of localization - Support 5 ms period for IMU explicitly

1.2.2 (2022-06-22)

  • Fixes

    : - Memory corruption under adverse conditions

  • Commits

    : - Merge pull request #66 from thomasemter/dev/next2 Fix memory corruption - Fix parameter warnings - Reset buffer size to 16384 - Update changelog - Fix memory corruption - Replace maps with unordered_maps - Overload timestamp function - Fix frame ids for INS msgs - Add define to avoid usage of deprecated header - Change readme on gps-msgs packet - Add info on user credentials - Fix spelling in readme - Merge remote-tracking branch \'upstream/ros2\' into dev/next2 - Add comment for heading from pose - Contributors: Thomas Emter, Tibor Dome

1.2.1 (2022-05-16)

  • New Features

    : - Add login credentials - Activate NTP server if use_gnss_time is set to true

  • Improvements

    : - Add NED option to localization

  • Fixes

    : - IMU orientation for ROS axis convention

  • Commits

    : - Merge pull request #63 from thomasemter/dev/next2 Small fixes and additions - Merge pull request #60 from wep21/support-rolling fix: modify build error for rolling/humble - Revert change for deprecation warning in Humble - Change links to reflect ROS2 - Amend readme regarding robot_localization - Fix compiler warnings for humble - Add more explanations for IMU orientation in ROS convention - Fix formatting in readme - Fix package name in readme - Update readme - Update changelog - Fix IMU orientation for ROS axis orientation - Activate NTP only if GNSS time is used - Add NED option to localization - Set NMEA header to GP - Update readme and changelog - Activate NTP server - Add credentials for access control - fix: modify build error for rolling/humble - Contributors: Daisuke Nishimatsu, Thomas Emter, Tibor Dome

1.2.0 (2022-04-27)

  • New Features

    : - Add option to use ROS axis orientations according to REP103 - Add frame_id parameters - Add option to get frames from tf - Publishing of cartesian localization in UTM (topic and/or tf) for INS - Publishing of IMU topic for INS - Publishing of MeasEpoch - ROS2 branch

  • Improvements

    : - Add multi antenna option - Increase number of SBF streams - Add option to set polling_period to \"on change\" - Increased buffer size from 8192 to 131072 bytes - Add endianess aware parsers - Only publish topics set to true - Add parameter to switch DEBUG logging on and off - Change GPxxx messages to ROS built-in types - Remove duplicate INS msg types

  • Fixes

    : - Setting of antenna type - Publishing rate interconnections of gpsfix and velcovgeodetic - Missing quotes for antenna type - Broken attitude parsing pose and gpsfix from INS - IMU orientation was not sent to Rx - Graceful shutdown of threads

  • Commits

    : - Merge branch \'dev\' - Prepare new release - Prepare new release - Merge pull request #53 from thomasemter/dev/refactor Very last changes - Add geographic lib dependency to package.xml - Add comment for frame of main antenna - Move utm zone locking section in readme - Reformulate readme section on frames - Merge pull request #52 from thomasemter/dev/refactor Last changes - Change frame id back to poi_frame_id - Make error log more explicit - Merge pull request #49 from thomasemter/dev/refactor Improve IMU blocks sync and do-not-use value handling - Fix buffer size in changelog - Turn off Nagle\'s algorithm for TCP - Fix changelog formatting - Fix readme - Set default base frame to base_link - Fix valid tow check logic - Increase buffer size for extreme stress tests - Fix crc check - Fix and streamline tf handling - Add checks for validity of values - Fix rad vs deg - Update changelog - Add some comments - Set stdDevMask to values > 0.0 in node - Set stdDevMask to values > 0.0 - Add info on RNDIS and set it to default - Increase default serial baud rate - Add parameter to set log level to debug - Change defaults for publishers in node - Put publish params together and fix mismatch in readme - Improve IMU blocks sync and do-not-use value handling - Merge pull request #48 from thomasemter/dev/refactor Fix measepoch not publishing without gpsfix - Fix measepoch not publishing without gpsfix - Merge pull request #47 from thomasemter/dev/refactor Dev/refactor - Publish only messages set to true - Remove leftover declaration - Merge branch \'dev/endianess_agnostic\' into dev/refactor - Update readme to reflect endianess aware parsing - Remove msg smart pointers - Fix array assertion failure - Cleanup - Add ReceiverStatus parser - Add QualityInd parser - Add DOP parser - Add ReceiverSetup parser - Fix MeasEpoch and ChannelStatus parsers, add measepoch publishing - Add ChannelStatus parser - Add MeasEpoch parser - Add IMU and VelSensor setup parsers - Add Cov SBF parsers - Add templated qi parser function - Add AttEuler+Cov parser - Revert ordering change inside INSNav ROS msgs - Add ExtSensorMeas parser - Add PVT parsers - Add range checks to parsers - Replace INSNav grammar with parsers - Test parser vs. grammar for better performance - Fix sb_list check - Add IMU and VelSensor setup grammars - Move adapt ROS header to typedefs.h - Add revision check to MeasEpoch - Fix ReceiverStatus grammar - Extend ReceiverSetup and add revision checks - Change logger and fix loop range - Remove reserved bytes from parsing - Remove obsolete structs - Directly parse Cov SBFs to ROS msg - Directly parse PVT SBFs, remove obsolete ids - Rename rev to revision - Fix block header parsing - Directly parse AttEuler to ROS msg - Directly parse to ROS msgs for INSNavXxx - Exchange pow with square function and remove casts - Merge pull request #46 from thomasemter/dev/refactor Dev/refactor - Simplify sync bytes check - Move tow/wnc to BlockHeader - Adjust order in INSNav ros msgs - Fix INSNav grammars - Change BlockHeader structure - Remove length ref from header - Rectify sb_list check of INSNavXxx - Add automtatic activation of multi-antenna mode - Merge branch \'dev/refactor\' of https://github.com/thomasemter/septentrio_gnss_driver into dev/refactor - Add automtatic activation of multi-antenna mode - Fix wrong scope of phoenix::ref variables - Fix AttEuler grammar - Add max size checks to QualityInd and ReceiverStatus - Replace locals with phoenix::ref in grammars - Add revision dependent parsing to PVTs - Change offset check to epsilon - Change offset check to epsilon - Fix parsing checks - Set has arrived to false on parsing error - Add INSNav grammars - Add abs to offset check - Add abs to offset check - Add Cov grammars - Remove superfluous typdefs of structs - Add ReceiverStatus grammar - Add QualityINd grammar - Merge pull request #45 from thomasemter/dev/refactor Dev/refactor - Add id check to header grammar - Add id check to header grammar - Add ReceiverSetup grammar - Add DOP grammar - Directly intialize vector to parse - Add MeasEpoch grammar - Remove duplicate msg types - Remove obsolete include - Add revision and length return to header grammar - Merge branch \'feature/endianess_agnostic\' into dev/endianess_agnostic - Make multi_antenna option also usable for gnss - Add typedefs plus some minor changes - Add warning concerning pitch angle if antennas are rotated - Add multi antenna option to ins and fix antenna offset decimal places trimming - Fix identation - Distinguish between gnss and ins for spatial config from tf - Merge pull request #43 from thomasemter/dev/refactor Dev/refactor - Add vehicle frame for clarity - Handle missing tf more gently - Merge branch \'dev/spatial_config_via_tf\' into dev/refactor - Update readme - Fix antenna offset from tf - Add automatic publishing of localization if tf is activated - Add automatic publishing of localization if tf is activated - Add spatial config via tf, to be tested - Fix crashes due to parsing errors (replacing uncatched throws) - Add tf broadcasting - Add comments - Add localization in UTM output - Add check to IMU msg sync - Change msg sync to allow for 200 Hz IMU msgs - Add ROS IMU msg - Fix IMU setup message attitude conversion - Fix pose from INS data - Fix IMU raw data rotation compensation - Make antenna attitude offset usable by GNSS - Add ros directions option to pose and fix covariances - Update readme - Merge branch \'feature/ros_axis_orientation\' into dev/refactor - Add nmea_msgs dependencies - Merge branch \'dev/nmea\' into dev/refactor - Update readme - Update readme - Add antenna offsets to conversions - Fix IMU orientation conversion - Change ExtSensorMead temperature to deg C - Add axis orientation info to readme - Fix IMU axis orientation - Change get int param - Update readme to reflect removal of aux antenna offset - Fix different antenna setup message for INS and remove obsolete aux1 antenna offset for GNSS - Fix ExtSensorMeas message filling - Fix ExtSensorMeas message to reflect available fields - Fix missing INS blocks - Fix missing INS blocks - WIP, introduce ros axis orientation option, to be tested - Add option to set pvt rate to OnChange - Add comment on NTP to readme - Change to nmea_msgs - Add automatic addition of needed sub messages - Comment out setting debug level - Add comments and fix spelling errors - Merge pull request #42 from thomasemter/dev/refactor Dev/refactor - Change to quaternion msg typedef - Comment out debug logging - Remove filling of seq field - Change msg definitions to be compatible with ROS2 - Update readme - Change make_shared for portability and add more typedefs - Add get param int fallback for numeric antenna serial numbers - Change Attitude to be published with pvt rate - Add log identifier - Add checks for relevant ros params - Concatenate multiple SBF blocks in streams - Move main into own file - Move get ros time to AsyncManager - Remove obsolete param comment - Move get ros params to base class - Change to nsec timestamp internally - Add publishing functionality to node base class - Move node handle ptr and functions to base class and rename - Add stamp to nmea parsing - Add logging in PcapReader - Add logging in CircularBuffer - Add missed logging - Add logging in AsyncManager - Add getTime function - Add logging in RxMessage - Add logging in CallbackHandlers - Add log function to node by polymorphism, logging in Comm_OI - Fix wait function and force use_gnss_time when reading from file - Add thread shutdown and remove spurious delete - Add typedefs for ins messages - Add typedefs for gnss messages - Add typedefs for ros messages - Refine shutdown - Fix shutdown escalating to SIGTERM - Move waiting for response in send function - Make functions private - Change crc to C++ - Fix variable name - Remove global variables from node cpp file - Move more global settings to settings struct - Move more global settings to settings struct - Move global settings to settings struct - Move more functions to Comm_IO - Move settings to struct and configuration to Comm_IO - Merge branch \'dev/change_utc_calculation\' into dev/refactor - Remove obsolete global variables - Move g_unix_time to class - Make has_arrived booleans class memebers and rx_message a persistent class - Make node handle a class member - Fix parsing of ID and rev - Finish ChannelStatusGrammar, to be tested - WIP, partially fix ChannelStatusGrammar - Add SBF length parsing utility - Insert spirit parsers - WIP, add omission of padding bytes - WIP, add more spirit parsers - Add parsing utilities for tow, wnc and ID - Move getId/Tow/Wnc to parsing utilities - Change UTC calculation to use tow and wnc - WIP, add boost spirit and endian buffers - Change UTC calculation to use tow and wnc

  • ROS2 Commits

    : - Prepare ros2 release - Merge pull request #54 from thomasemter/dev/ros2 ROS2 branch - Port driver to ros2

  • Change UTC calculation to use tow and wnc

  • Contributors: Thomas Emter, Tibor Dome, tibordome

1.0.8 (2021-10-23)

  • Added INS Support

1.0.7 (2021-05-18)

  • Clang formatting, publishing from SBF log, play-back of PCAP files

1.0.6 (2020-10-16)

  • ROSaic binary installation now available on Melodic & Noetic

1.0.5 (2020-10-15)

  • changed repo name
  • v1.0.4
  • 1.0.3
  • Merge pull request #22 from septentrio-gnss/local_tibor New changelog
  • New changelog
  • Merge pull request #21 from septentrio-gnss/local_tibor Added rosdoc.yaml file
  • Merge pull request #20 from septentrio-gnss/local_tibor Improved doxygen annotations
  • Merge pull request #19 from septentrio-gnss/local_tibor Improved doxygen annotations
  • Update README.md
  • Merge pull request #18 from septentrio-gnss/local_tibor Adopted ROS and C++ conventions, added ROS diagnostics msg,
  • Update README.md
  • Update README.md
  • Update README.md
  • Contributors: septentrio-users, tibordome

1.0.4 (2020-10-11)

  • Added rosdoc.yaml file
  • Improved doxygen annotations
  • Improved doxygen annotations
  • Adopted ROS and C++ conventions, added ROS diagnostics msg, removed ROS garbage value bug, added auto-detection of SBF arrival order for composite ROS msgs
  • Merge branch \'master\' of https://github.com/septentrio-gnss/rosaic
  • NTRIP with Datalink, circular buffer, reading connection descriptor, new messages
  • Update README.md
  • Contributors: septentrio-users, tibordome

1.0.3 (2020-09-30)

  • Add new config/rover.yaml file
  • Add config/rover.yaml to .gitignore
  • Merge pull request #17 from septentrio-gnss/local_tibor NTRIP with Datalink, circular buffer, reading connection descriptor..
  • Merge branch \'local_tibor\'
  • NTRIP with Datalink, circular buffer, reading connection descriptor, new messages
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #16 from septentrio-gnss/local_tibor NTRIP parameters added, reconnect_delay_s implemented,
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #15 from tibordome/local_tibor GPSFix completed, datum as new parameter
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #14 from tibordome/local_tibor GPSFix completed, datum as new parameter
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #13 from tibordome/local_tibor Added AttCovEuler.msg and AttEuler.msg
  • Merge pull request #12 from tibordome/local_tibor Fixed service field of NavSatStatus
  • Contributors: Tibor Dome, septentrio-users, tibordome

1.0.2 (2020-09-25)

  • NTRIP parameters added, reconnect_delay_s implemented, package.xml updated, ROSaic now detects connection descriptor automatically, mosaic serial port parameter added
  • GPSFix completed, datum as new parameter, ANT type and marker-to-arp distances as new parameters, BlockLength() method corrected, sending multiple commands to Rx corrected by means of mutex
  • Contributors: tibordome

1.0.1 (2020-09-22)

  • GPSFix completed, datum as new parameter, ANT type and marker-to-arp distances as new parameters, BlockLength() method corrected, sending multiple commands to Rx corrected by means of mutex
  • Added AttCovEuler.msg and AttEuler.msg
  • Fixed service field of NavSatStatus, fixed ROS header\'s seq field of each published ROS message, added write method for sending commands to Rx, successfully tested, added AttEuler, added AttCovEuler
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #11 from tibordome/local_tibor rosconsole_backend_interface dependency not needed
  • rosconsole_backend_interface dependency not needed
  • Merge pull request #10 from tibordome/local_tibor rosconsole_log4cxx dep not needed
  • rosconsole_log4cxx dep not needed
  • Merge pull request #9 from tibordome/local_tibor rosconsole_log4cxx dep not needed
  • rosconsole_log4cxx dep not needed
  • Merge pull request #8 from tibordome/local_tibor Local tibor
  • Update README.md
  • Merge pull request #7 from tibordome/local_tibor Ready for First Release
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #6 from tibordome/local_tibor Local tibor
  • Merge pull request #5 from tibordome/local_tibor TCP seems to work
  • Contributors: Tibor Dome, tibordome

1.0.0 (2020-09-11)

  • Ready for first release
  • Added Gpgga.msg and PosCovGeodetic.msg files
  • Ready for First Release
  • Ready for first release
  • Ready for first release
  • Ready for first release
  • TCP bug removed
  • TCP bug removed
  • TCP seems to work
  • Merge pull request #4 from tibordome/v0.2 V0.2
  • PVTCartesian and PVTGeodetic publishing works on serial
  • PVTCartesian and PVTGeodetic publishing works on serial
  • Merge pull request #3 from tibordome/v0.2 Add doxygen_out and Doxyfile 2nd trial
  • Add doxygen_out and Doxyfile 2nd trial
  • Merge pull request #2 from tibordome/v0.1 Add doxygen_out and Doxyfile
  • Add doxygen_out and Doxyfile
  • Update README.md
  • Create README.md
  • Update LICENSE
  • Merge pull request #1 from tibordome/add-license-1 Create LICENSE
  • Create LICENSE
  • Create LICENSE
  • Commit
  • Successfully tested publishing to /gpgga topic via serial
  • To make sure master branch exists
  • Contributors: Tibor Dome, tibordome

Wiki Tutorials

See ROS Wiki Tutorials for more details.

Source Tutorials

Not currently indexed.

Recent questions tagged septentrio_gnss_driver at Robotics Stack Exchange

septentrio_gnss_driver package from septentrio_gnss_driver repo

septentrio_gnss_driver

Package Summary

Tags No category tags.
Version 1.3.2
License BSD 3-Clause License
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/septentrio-gnss/septentrio_gnss_driver.git
VCS Type git
VCS Version ros2
Last Updated 2023-11-22
Dev Status MAINTAINED
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

ROSaic: C++ driver for Septentrio's mosaic receivers and beyond

Additional Links

Maintainers

  • Tibor Dome
  • Septentrio

Authors

  • Tibor Dome

ROSaic = ROS + mosaic

Overview

This repository hosts drivers for ROS (Melodic and Noetic) and ROS 2 (Foxy, Galactic, Humble, Rolling, and beyond) - written in C++ - that work with mosaic and AsteRx - two of Septentrio's cutting-edge GNSS and GNSS/INS receiver families - and beyond. The ROS 2 version is available in this branch, whereas the ROS 1 version is available in the branch master.

Main Features: - Supports Septentrio's single antenna GNSS, dual antenna GNSS and INS receivers - Supports serial, TCP/IP and USB connections, the latter being compatible with both serial (RNDIS) and TCP/IP protocols - Supports several ASCII (including key NMEA ones) messages and SBF (Septentrio Binary Format) blocks - Reports status of AIM+ (Advanced Interference Mitigation including OSNMA) anti-jamming and anti-spoofing. - Can publish nav_msgs/Odometry message for INS receivers - Can blend SBF blocks PVTGeodetic, PosCovGeodetic, ChannelStatus, MeasEpoch, AttEuler, AttCovEuler, VelCovGeodetic and DOP in order to publish gps_common/GPSFix and sensor_msgs/NavSatFix messages - Supports axis convention conversion as Septentrio follows the NED convention, whereas ROS is ENU. - Easy configuration of multiple RTK corrections simultaneously (via NTRIP, TCP/IP stream, or serial) - Can play back PCAP capture logs for testing purposes - Tested with the mosaic-X5, mosaic-H, AsteRx-m3 Pro+ and the AsteRx-SBi3 Pro receiver - Easy to add support for more log types

Please let the maintainers know of your success or failure in using the driver with other devices so we can update this page appropriately.

Dependencies

The ros2 branch for this driver functions on ROS Foxy, Galactic, Rolling, and Humble (Ubuntu 20.04 or 22.04 respectively). It is thus necessary to install the ROS version that has been designed for your Linux distro.

Additional ROS packages have to be installed for the NMEA and GPSFix messages.

sudo apt install ros-$ROS_DISTRO-nmea-msgs ros-$ROS_DISTRO-gps-msgs.

The serial and TCP/IP communication interface of the ROS driver is established by means of the Boost C++ library. In the unlikely event that the below installation instructions fail to install Boost on the fly, please install the Boost libraries via

sudo apt install libboost-all-dev.

Compatiblity with PCAP captures are incorporated through pcap libraries. Install the necessary headers via

sudo apt install libpcap-dev.

Conversions from LLA to UTM are incorporated through GeographicLib. Install the necessary headers via

sudo apt install libgeographic-dev

Usage

Binary Install The binary release is now available for Foxy and Galactic. To install the binary package, simply run `sudo apt-get install ros-$ROS_DISTRO-septentrio-gnss-driver`.
Build from Source The package has to be built from source using [`colcon`](https://docs.ros.org/en/humble/Tutorials/Beginner-Client-Libraries/Colcon-Tutorial.html): ``` source /opt/ros/${ROS_DISTRO}/setup.bash # In case you do not use the default shell of Ubuntu, you need to source another script, e.g. setup.sh. mkdir -p ~/septentrio/src # Note: Change accordingly depending on where you want your package to be installed. cd ~/septentrio/src git clone https://github.com/septentrio-gnss/septentrio_gnss_driver git checkout ros2 # Install mentioned dependencies (`sudo apt install ros-$ROS_DISTRO-nmea_msgs ros-$ROS_DISTRO-gps-msgs libboost-all-dev libpcap-dev libgeographic-dev`) colcon build --packages-up-to septentrio_gnss_driver # Be sure to call colcon build in the root folder of your workspace. Launch files are installed, so changing them on the fly in the source folder only works with installing by symlinks: add `--symlink-install` echo "source ~/septentrio/devel/setup.bash" >> ~/.bashrc # It is convenient if the ROS environment variable is automatically added to your bash session every time a new shell is launched. Again, this works for bash shells only. Also note that if you have more than one ROS distribution installed, ~/.bashrc must only source the setup.bash for the version you are currently using. source ~/.bashrc ``` Run tests ``` colcon test --packages-select septentrio_gnss_driver --event-handlers console_direct+ ```
Notes Before Usage + In your bash sessions, navigating to the ROSaic package can be achieved from anywhere with no more effort than `roscd septentrio_gnss_driver`. + The driver assumes that our anonymous access to the Rx grants us full control rights. This should be the case by default, and can otherwise be changed with the `setDefaultAccessLevel` command. If user control is in place user credentials can be given by parameters `login.user` and `login.password`. + ROSaic only works from C++17 onwards due to std::any() etc. + Note for setting hw_flow_control: This is a string parameter, setting it to off without quotes leads to the fact that it is not read in correctly. + Note for setting ant_(aux1)_serial_nr: This is a string parameter, numeric only serial numbers should be put in quotes. If this is not done a warning will be issued and the driver tries to parse it as integer. + Once the colcon build or binary installation is finished, adapt the `config/rover.yaml` file according to your needs or assemble a new one. Launch as composition with `ros2 launch septentrio_gnss_driver rover.launch.py` to use `rover.yaml` or add `file_name:=xxx.yaml` to use a custom config. Alternatively launch as node with `ros2 launch septentrio_gnss_driver rover_node.launch.py` to use `rover_node.yaml` or add `file_name:=xxx.yaml` to use a custom config. Specify the communication parameters, the ROS messages to be published, the frequency at which the latter should happen etc. + Besides the aforementioned config file `rover.yaml` containing all parameters, specialized launch files for GNSS `config/gnss.yaml` and INS `config/ins.yaml` respectively contain only the relevant parameters in each case. - NOTE: Unless `configure_rx` is set to `false`, this driver will overwrite the previous values of the parameters, even if the value is left to zero in the "yaml" file. + The driver was developed and tested with firmware versions >= 4.10.0 for GNSS and >= 1.3.2 for INS. Receivers with older firmware versions are supported but some features may not be available. Known limitations are: * GNSS with firmware < 4.10.0 does not support IP over USB. * GNSS with firmware < 4.12.1 does not support OSNMA. * INS with firmware < 1.3.2 does not support NTP. * INS with firmware < 1.4 does not support OSNMA. * INS with firmware < 1.4.1 does not support improved VSM handling allowing for unknown variances. * INS with firmware 1.2.0 does not support velocity aiding. * INS with firmware 1.2.0 does not support setting of initial heading. + Known issues: * UDP over USB: Blocks are sent twice on GNSS with firmware <= 4.12.1 and INS with firmware <= 1.4. For GNSS it is fixed in version 4.14 (released on June 15th 2023), for INS it will be fixed in to-be-released 1.4.1 (expected in November 2023). + If `use_ros_axis_orientation` to `true` axis orientations are converted by the driver between NED (Septentrio: yaw = 0 is north, positive clockwise) and ENU (ROS: yaw = 0 is east, positive counterclockwise). There is no conversion when setting this parameter to `false` and the angles will be consistent with the web GUI in this case. :
``` # Example configuration Settings for the Rover Rx device: tcp://192.168.3.1:28784 serial: baudrate: 921600 hw_flow_control: "off" tcp: ip_server: "" port: 0 udp: ip_server: "" port: 0 unicast_ip: "" configure_rx: true login: user: "" password: "" osnma: mode: "off" ntp_server: "" keep_open: true frame_id: gnss imu_frame_id: imu poi_frame_id: base_link vsm_frame_id: vsm aux1_frame_id: aux1 vehicle_frame_id: base_link insert_local_frame: false local_frame_id: odom get_spatial_config_from_tf: true lock_utm_zone: true use_ros_axis_orientation: true receiver_type: gnss datum: Default poi_to_arp: delta_e: 0.0 delta_n: 0.0 delta_u: 0.0 att_offset: heading: 0.0 pitch: 0.0 ant_type: Unknown ant_aux1_type: Unknown ant_serial_nr: Unknown ant_aux1_serial_nr: Unknown leap_seconds: 18 polling_period: pvt: 500 rest: 500 use_gnss_time: false latency_compensation: false rtk_settings: ntrip_1: id: "NTR1" caster: "1.2.3.4" caster_port: 2101 username: "Asterix" password: "password" mountpoint: "mtpt1" version: "v2" tls: true fingerprint: "AA:BB:56:78:90:12: ... 78:90:12:34" rtk_standard: "RTCMv3" send_gga: "auto" keep_open: true ntrip_2: id: "NTR3" caster: "5.6.7.8" caster_port: 2101 username: "Obelix" password: "password" mountpoint: "mtpt2" version: "v2" tls: false fingerprint: "" rtk_standard: "RTCMv2" send_gga: "auto" keep_open: true ip_server_1: id: "IPS3" port: 28785 rtk_standard: "RTCMv2" send_gga: "auto" keep_open: true ip_server_2: id: "IPS5" port: 28786 rtk_standard: "CMRv2" send_gga: "auto" keep_open: true serial_1: port: "COM1" baud_rate: 230400 rtk_standard: "auto" send_gga: "sec1" keep_open: true serial_2: port: "COM2" baud_rate: 230400 rtk_standard: "auto" send_gga: "off" keep_open: true publish: # For both GNSS and INS Rxs navsatfix: false gpsfix: true gpgga: false gprmc: false gpst: false measepoch: false pvtcartesian: false pvtgeodetic: true basevectorcart: false basevectorgeod: false poscovcartesian: false poscovgeodetic: true velcovcartesian: false velcovgeodetic: false atteuler: true attcoveuler: true pose: false twist: false diagnostics: false aimplusstatus: true galauthstatus: false # For GNSS Rx only gpgsa: false gpgsv: false # For INS Rx only insnavcart: false insnavgeod: false extsensormeas: false imusetup: false velsensorsetup: false exteventinsnavcart: false exteventinsnavgeod: false imu: false localization: false tf: false localization_ecef: false tf_ecef: false # INS-Specific Parameters ins_spatial_config: imu_orientation: theta_x: 0.0 theta_y: 0.0 theta_z: 0.0 poi_lever_arm: delta_x: 0.0 delta_y: 0.0 delta_z: 0.0 ant_lever_arm: x: 0.0 y: 0.0 z: 0.0 vsm_lever_arm: vsm_x: 0.0 vsm_y: 0.0 vsm_z: 0.0 ins_initial_heading: auto ins_std_dev_mask: att_std_dev: 5.0 pos_std_dev: 10.0 ins_use_poi: true ins_vsm: source: "twist" config: [true, false, false] variances_by_parameter: true variances: [0.1, 0.0, 0.0] ip_server: id: "IPS2" port: 28787 keep_open: true serial: port: "COM3" baud_rate: 115200 keep_open: true # Logger activate_debug_log: false ``` In order to launch ROSaic, one must specify all `arg` fields of the `rover.py` file which have no associated default values, i.e. for now only the `file_name` field. Hence, the launch command reads `ros2 launch septentrio_gnss_driver rover.py file_name:=rover.yaml`. If multiple port are utilized for RTK corrections and/or VSM, which shall be closed after driver shutdown (`keep_open: false`), make sure to give the driver enough time to gracefully shutdown as closing the ports takes a few seconds. This can be accomplished in the launch files by increasing the timeout of SIGTERM (e.g. `sigterm_timeout = '10',`), see example launch files`rover.py`and `rover_node.py` respectively.

Inertial Navigation System (INS): Basics

  • An Inertial Navigation System (INS) is a device which takes the rotation and acceleration solutions as obtained from its Inertial Measurement Unit (IMU) and combines those with position and velocity information from the GNSS module. Compared to a GNSS system with 7D or 8D (dual-antenna systems) phase space solutions, the combined, Kalman-filtered 9D phase space solution (3 for position, 3 for velocity, 3 for orientation) of an INS is more accurate, more precise and more stable against GNSS outages.
  • The IMU is typically made up of a 3-axis accelerometer, a 3-axis gyroscope and sometimes a 3-axis magnetometer and measures the system's angular rate and acceleration.

    Measure and Compensate for IMU-Antenna Lever Arm

    • The IMU-antenna lever-arm is the relative position between the IMU reference point and the GNSS Antenna Reference Point (ARP), measured in the vehicle frame.
    • In case of AsteRx SBi3, the IMU reference point is clearly marked on the top panel of the receiver. It is important to compensate for the effect of the lever arm, otherwise the receiver may not be able to calculate an accurate INS position.
    • The IMU/antenna position can be changed by specifying the lever arm's x,yand z parameters in the config.yaml file under the ins_spatial_config.ant_lever_arm parameter.

    Screenshot from 2021-08-03 09-23-19 (1)

    Compensate for IMU Orientation + It is important to take into consideration the mounting direction of the IMU in the body frame of the vehicle. For e.g. when the receiver is installed horizontally with the front panel facing the direction of travel, we must compensate for the IMU’s orientation to make sure the IMU reference frame is aligned with the vehicle reference frame. The IMU position and orientation is printed on the top panel, cf. image below. + The IMU's orientation can be changed by specifying the orientation angles theta_x,theta_yand theta_z in the config.yaml file under ins_spatial_config.imu_orientation + The below image illustrates the orientation of the IMU reference frame with the associated IMU orientation for the depicted installation. Note that for use_ros_axis_orientation: true sensor_default is the top left position.

    Capture (1)

  • These Steps should be followed to configure the receiver in INS integration mode:

    • Specify receiver_type: INS
    • Specify the orientation of the IMU sensor with respect to your vehicle, using the ins_spatial_config.imu_orientation parameter.
    • Specify the IMU-antenna lever arm in the vehicle reference frame. This is the vector starting from the IMU reference point to the ARP of the main GNSS antenna. This can be done by means of the ins_spatial_config.ant_lever_arm parameter.
    • Specify ins_spatial_config.vsm_lever_arm if measurements of a velocity sensor is available.
    • Alternatively the lever arms may be specified via tf. Set get_spatial_config_from_tfto true in this case.
    • If the point of interest is neither the IMU nor the ARP of the main GNSS antenna, the vector between the IMU and the point of interest can be provided with the ins_solution/poi_lever_arm parameter.
  • For further more information about Septentrio receivers, visit Septentrio support resources or check out the user manual and reference guide of the AsteRx SBi3 receiver.

ROSaic Parameters

The following is a list of ROSaic parameters found in the config/rover.yaml file. * Parameters Configuring Communication Ports and Processing of GNSS and INS Data

Connectivity Specs

  • device: location of main device connection. This interface will be used for setup communication and VSM data for INS. Incoming data streams of SBF blocks and NMEA sentences are recevied either via this interface or a static IP server for TCP and/or UDP. The former will be utilized if section stream_device.tcp and stream_device.udp are not configured.
    • serial:xxx format for serial connections,where xxx is the device node, e.g. serial:/dev/ttyS0. If using serial over USB, it is recommended to specify the port by ID as the Rx may get a different ttyXXX on reconnection, e.g. serial:/dev/serial/by-id/usb-Septentrio_Septentrio_USB_Device_xyz.
    • file_name:path/to/file.sbf format for publishing from an SBF log
    • file_name:path/to/file.pcap format for publishing from PCAP capture.
      • Regarding the file path, ROS_HOME=`pwd` in front of roslaunch septentrio... might be useful to specify that the node should be started using the executable's directory as its working-directory.
    • tcp://host:port format for TCP/IP connections
      • 28784 should be used as the default (command) port for TCP/IP connections. If another port is specified, the receiver needs to be (re-)configured via the Web Interface before ROSaic can be used.
      • An RNDIS IP interface is provided via USB, assigning the address 192.168.3.1 to the receiver. This should work on most modern Linux distributions. To verify successful connection, open a web browser to access the web interface of the receiver using the IP address 192.168.3.1.
    • default: tcp://192.168.3.1:28784
  • serial: specifications for serial communication
    • baudrate: serial baud rate to be used in a serial connection. Ensure the provided rate is sufficient for the chosen SBF blocks. For example, activating MeasEpoch (also necessary for /gpsfix) may require up to almost 400 kBit/s.
    • rx_serial_port: determines to which (virtual) serial port of the Rx we want to get connected to, e.g. USB1 or COM1
    • hw_flow_control: specifies whether the serial (the Rx's COM ports, not USB1 or USB2) connection to the Rx should have UART hardware flow control enabled or not
      • off to disable UART hardware flow control, RTS|CTS to enable it
    • default: 921600, USB1, off
  • stream_device: If left unconfigured, by default device is utilized for the data streams. Within stream_device static IP servers may be defined instead. In config mode (configure_rx set to true), TCP will be prioritized over UDP. If Rx is pre-configured, both may be set simultaneously.
    • tcp: specifications for static TCP server of SBF blocks and NMEA sentences.
      • ip_server: IP server of Rx to be used, e.g. “IPS1”.
      • port: UDP destination port.
    • udp: specifications for low latency UDP reception of SBF blocks and NMEA sentences.
      • ip_server: IP server of Rx to be used, e.g. “IPS1”.
      • port: UDP destination port.
      • unicast_ip: Set to computer's IP to use unicast (optional). If not set multicast will be used.
  • login: credentials for user authentication to perform actions not allowed to anonymous users. Leave empty for anonymous access.
    • user: user name
    • password: password

OSNMA

  • osnma: Configuration of the Open Service Navigation Message Authentication (OSNMA) feature.
    • mode: Three operating modes are supported: off where OSNMA authentication is disabled, loose where satellites are included in the PVT if they are successfully authenticated or if their authentication status is unknown, and strict where only successfully-authenticated satellites are included in the PVT. In case of strict synchronization via NTP is mandatory.
      • default: off
    • ntp_server: In strict mode, OSNMA authentication requires the availability of external time information. In loose mode, this is optional but recommended for enhanced security. The receiver can connect to an NTP time server for this purpose. Options are default to let the receiver choose an NTP server or specify one like pool.ntp.org for example.
      • default: ""
    • keep_open: Wether OSNMA shall be kept active on driver shutdown.
      • default: true

Receiver Configuration

+ configure_rx: Wether to configure the Rx according to the config file. If set to `false`, the Rx has to be configured via the web interface and the settings must be saved. On the driver side communication has to set accordingly to serial, TCP or UDP (TCP and UDP may even be used simultaneously in this case). For TCP communication it is recommended to use a static TCP server (`stream_device.tcp.ip_server` and `stream_device.tcp.port`), since dynamic connections (`device` is tcp) are not guaranteed to have the same id on reconnection. It should also be ensured that obligatory SBF blocks are activated (as of now: ReceiverTime if `use_gnss_time` is set to `true`; `PVTGeodetic`or `PVTCartesian` if latency compensation for PVT related blocks shall be used). Further, if ROS messages compiled from multiple SBF blocks, it should be ensured that all necessary blocks are activated with matching periods, details can be found in section [ROS Topic Publications](#ros-topic-publications). The messages that shall be published still have to be set to `true` in the *NMEA/SBF Messages to be Published* section. Also, parameters concerning the connection and node setup are still relevant (sections: *Connectivity Specs*, *receiver type*, *Frame IDs*, *UTM Zone Locking*, *Time Systems*, *Logger*).
  + default: true

Receiver Type

  • receiver_type: This parameter is to select the type of the Septentrio receiver
    • gnss for GNSS receivers.
    • ins for INS receivers.
    • default: gnss
  • multi_antenna: Whether or not the Rx has multiple antennas.
    • default: false

Frame IDs

  • frame_id: name of the ROS tf frame for the Rx, placed in the header of published GNSS messages. It corresponds to the frame of the main antenna.
    • In ROS, the tf package lets you keep track of multiple coordinate frames over time. The frame ID will be resolved by tf_prefix if defined. If a ROS message has a header (all of those we publish do), the frame ID can be found via rostopic echo /topic, where /topic is the topic into which the message is being published.
    • default: gnss
  • imu_frame_id: name of the ROS tf frame for the IMU, placed in the header of published IMU message
    • default: imu
  • poi_frame_id: name of the ROS tf frame for the POI, placed in the child frame_id of localization if ins_use_poi is set to true.
    • default: base_link
  • vsm_frame_id: name of the ROS tf frame for the velocity sensor.
    • default: vsm
  • aux1_frame_id: name of the ROS tf frame for the aux1 antenna.
    • default: aux1
  • vehicle_frame_id: name of the ROS tf frame for the vehicle. Default is the same as poi_frame_id but may be set otherwise.
    • default: base_link
  • local_frame_id: name of the ROS tf frame for the local frame.
    • default: odom
  • insert_local_frame: Wether to insert a local frame to published tf according to ROS REP 105. The transform from the local frame specified by local_frame_id to the vehicle frame specified by vehicle_frame_id has to be provided, e.g. by odometry. Insertion of the local frame means the transform between local frame and global frame is published instead of transform between vehicle frame and global frame.
    • default: false
  • get_spatial_config_from_tf: wether to get the spatial config via tf with the above mentioned frame ids. This will override spatial settings of the config file. For receiver type ins with multi_antenna set to true all frames have to be provided, with multi_antenna set to false, aux1_frame_id is not necessary. For type gnss with dual-antenna setup only frame_id, aux1_frame_id, and poi_frame_id are needed. For single-antenna gnss no frames are needed. Keep in mind that tf has a tree structure. Thus, poi_frame_id is the base for all mentioned frames.
    • default: false
  • use_ros_axis_orientation Wether to use ROS axis orientations according to ROS REP 103 for body related frames and geographic frames. Body frame directions affect INS lever arms and IMU orientation setup parameters. Geographic frame directions affect orientation Euler angles for INS+GNSS and attitude of dual-antenna GNSS. If use_ros_axis_orientation is set to true, the driver converts between the NED convention (Septentrio: yaw = 0 is north, positive clockwise), and ENU convention (ROS: yaw = 0 is east, positive counterclockwise). There is no conversion when setting this parameter to false and the angles will be consistent with the web GUI in this case.
    • If set to false Septentrios definition is used, i.e., front-right-down body related frames and NED (north-east-down) for orientation frames.
    • If set to true ROS definition is used, i.e., front-left-up body related frames and ENU (east-north-up) for orientation frames.
    • default: true

UTM zone locking + lock_utm_zone: wether the UTM zone of the initial localization is locked, i.e., this zone is kept even if a zone transition would occur. + default: true

Datum

  • datum: With this command, the datum the coordinates should refer to is selected. With setting it to Default, the datum depends on the positioning mode, e.g. WGS84 for standalone positioning.
    • Since the standardized GGA message does only provide the orthometric height (= MSL height = distance from Earth's surface to geoid) and the geoid undulation (distance from geoid to ellipsoid) for which non-WGS84 datums cannot be specified, it does not affect the GGA message.
    • default: Default

POI-ARP Offset

+ `poi_to_arp`: offsets of the main GNSS antenna reference point (ARP) with respect to the point of interest (POI = marker). Use for static receivers only.
+ The parameters `delta_e`, `delta_n` and `delta_u` are the offsets in the East, North and Up (ENU) directions respectively, expressed in meters.
+ All absolute positions reported by the receiver are POI positions, obtained by subtracting this offset from the ARP. The purpose is to take into account the fact that the antenna may not be located directly on the surveying POI.
+ default: `0.0`, `0.0` and `0.0`

Antenna Attitude Offset

+ `att_offset`: Angular offset between two antennas (Main and Aux) and vehicle frame
+ `heading`: The perpendicular (azimuth) axis can be compensated for by adjusting the `heading` parameter
+ `pitch`: Vertical (elevation) offset can be compensated for by adjusting the `pitch` parameter
+ default: `0.0`, `0.0` (degrees)

Antenna Specs

  • ant_type: type of your main GNSS antenna
    • For best positional accuracy, it is recommended to select a type from the list returned by the command lstAntennaInfo, Overview. This is the list of antennas for which the receiver can compensate for phase center variation.
    • By default and if ant_type does not match any entry in the list returned by lstAntennaInfo, Overview, the receiver will assume that the phase center variation is zero at all elevations and frequency bands, and the position will not be as accurate.
    • default: Unknown
  • ant_serial_nr: serial number of your main GNSS antenna
  • ant_aux1_type and ant_aux1_serial_nr: same for Aux1 antenna

Leap Seconds

  • leap_seconds: Leap seconds are automatically gathered from the receiver via the SBF block ReceiverTime. If a log file is used for simulation and this block was not recorded, the number of leap seconds that have been inserted up until the point of ROSaic usage can be set by this parameter.
    • At the time of writing the code (2020), the GPS time, which is unaffected by leap seconds, was ahead of UTC time by 18 leap seconds. Adapt the leap_seconds parameter accordingly as soon as the next leap second is inserted into the UTC time or in case you are using ROSaic for the purpose of simulations.

Polling Periods

  • polling_period.pvt: desired period in milliseconds between the polling of two consecutive PVTGeodetic, PosCovGeodetic, PVTCartesian and PosCovCartesian blocks and - if published - between the publishing of two of the corresponding ROS messages (e.g. septentrio_gnss_driver/PVTGeodetic.msg). Consult firmware manual for allowed periods. If the period is set to a lower value than the receiver is capable of, it will be published with the next higher period. If set to 0, the SBF blocks are output at their natural renewal rate (OnChange).
  • polling_period.rest: desired period in milliseconds between the polling of all other SBF blocks and NMEA sentences not addressed by the previous parameter, and - if published - between the publishing of all other ROS messages
    • default: 500 (2 Hz)

Time Systems

  • use_gnss_time: true if the ROS message headers' unix epoch time field shall be constructed from the TOW/WNC (in the SBF case) and UTC (in the NMEA case) data, false if those times shall be taken by the driver from ROS time. If use_gnss_time is set to true, make sure the ROS system is synchronized to an NTP time server either via internet or ideally via the Septentrio receiver since the latter serves as a Stratum 1 time server not dependent on an internet connection. The NTP server of the receiver is automatically activated on the Septentrio receiver (for INS/GNSS a firmware >= 1.3.3 is needed).
    • default: true
  • latency_compensation: Rx reports processing latency in PVT and INS blocks. If set to truethis latency is subtracted from ROS timestamps in related blocks (i.e., use_gnss_time set to false). Related blocks are INS, PVT, Covariances, and BaseVectors. In case of use_gnss_time set to true, the latency is already compensated within the RX and included in the reported timestamps.
    • default: false

RTK corrections

  • rtk_settings: determines RTK connection parameters
    • There are multiple possibilities to feed RTK corrections to the Rx. They may be set simultaneously and the Rx will choose the nearest source.
      • a) ntrip_# if the Rx has internet access and is able to receieve NTRIP streams from a caster. Up to three NTRIP connections are possible.
      • b) ip_server_# if corrections are to be receieved via TCP/IP for example over Data Link from Septentrio's RxTools is installed on a computer. Up to five IP server connections are possible.
      • c) serial_# if corrections are to be receieved via a serial port for example over radio link from a local RTK base or over Data Link from Septentrio's RxTools installed on a computer. Up to five serial connections are possible.
    • ntrip_#: for receiving corretions from an NTRIP caster (# is from 1 ... 3).
      • id: NTRIP connection NTR1, NTR2, or NTR3.
      • default: ""
      • caster: is the hostname or IP address of the NTRIP caster to connect to.
      • default: ""
      • caster_port: IP port of the NTRIP caster.
      • default: 2021
      • username: user name for the NTRIP caster.
      • default: ""
      • pasword: password for the NTRIP caster. The receiver encrypts the password so that it cannot be read back with the command "getNtripSettings".
      • default: ""
      • mountpoint: mount point of the NTRP caster to be used.
      • default: ""
      • version: argument specifies which version of the NTRIP protocol to use (v1 or v2).
      • default: "v2"
      • tls: determines wether to use TLS.
      • default: false
      • fingerprint: fingerprint to be used if the certificate is self-signed. If the caster’s certificate is known by a publicly-trusted certification authority, fingerprint should be left empty.
      • default: ""
      • rtk_standard: determines the RTK standard, options are auto, RTCMv2, RTCMv3, or CMRv2.
      • default: "auto"
      • send_gga: specifies whether or not to send NMEA GGA messages to the NTRIP caster, and at which rate. It must be one of auto, off, sec1, sec5, sec10 or sec60. In auto mode, the receiver automatically sends GGA messages if requested by the caster.
      • default: "auto"
      • keep_open: determines wether this connection shall be kept open. If set to true the Rx will still be able to receive RTK corrections to improve precision after driver is shut down.
      • default: true
    • ip_server_#: for receiving corretions via TCP/IP (# is from 1 ... 5).
      • id: specifies the IP server IPS1, IPS2, IPS3, IPS4, or IPS5. Note that ROSaic will send GGA messages on this connection if send_gga is set, such that in the Data Link application of RxTools one just needs to set up a TCP client to the host name as found in the ROSaic parameter device with the port as found in port. If the latter connection were connection 1 on Data Link, then connection 2 would set up an NTRIP client connecting to the NTRIP caster as specified in the above parameters in order to forward the corrections from connection 2 to connection 1.
      • default: ""
      • port: its port number of the connection that ROSaic establishes on the receiver. When selecting a port number, make sure to avoid conflicts with other services.
      • default: 0
      • rtk_standard: determines the RTK standard, options are auto, RTCMv2, RTCMv3, or CMRv2.
      • default: ""
      • send_gga: specifies whether or not to send NMEA GGA messages to the NTRIP caster, and at which rate. It must be one of auto, off, sec1, sec5, sec10 or sec60. In auto mode, the receiver sends with sec1.
      • default: "auto"
      • keep_open: determines wether this connection shall be kept open. If set to true the Rx will still be able to receive RTK corrections to improve precision after driver is shut down.
      • default: true
    • serial_#: for receiving corretions via serial connection (# is from 1 ... 5).
      • port: Serial connection COM1, COM2, COM3, USB1, or USB2 on which corrections could be forwarded to the Rx from a serially connected radio link modem or via Data Link for example.
      • default: ""
      • baud_rate: sets the baud rate of this port for genuine serial ports, i.e., not relevant for USB connection.
      • default: 115200
      • rtk_standard: determines the RTK standard, options are auto, RTCMv2, RTCMv3, or CMRv2.
      • default: "auto"
      • send_gga: specifies whether or not to send NMEA GGA messages to the NTRIP caster, and at which rate. It must be one of auto, off, sec1, sec5, sec10 or sec60. In auto mode, the receiver sends with sec1.
      • default: "auto"
      • keep_open: determines wether this connection shall be kept open. If set to true the Rx will still be able to receive RTK corrections to improve precision after driver is shut down.
      • default: true

INS Specs

+ `ins_spatial_config`: Spatial configuration of INS/IMU. Coordinates according to vehicle related frame directions chosen by `use_ros_axis_orientation` (front-left-up if `true` and front-right-down if `false`).
  + `imu_orientation`: IMU sensor orientation
    + Parameters `theta_x`, `theta_y` and `theta_z` are used to determine the sensor orientation with respect to the vehicle frame. Positive angles correspond to a right-handed (clockwise) rotation of the IMU with respect to its nominal orientation (see below). The order of the rotations is as follows: `theta_z` first, then `theta_y`, then `theta_x`.
    + The nominal orientation is where the IMU is upside down and with the `X axis` marked on the receiver pointing to the front of the vehicle. By contrast, for `use_ros_axis_orientation: true`, nominal orientation is where the `Z axis` of the IMU is pointing upwards and also with the `X axis` marked on the receiver pointing to the front of the vehicle.
    + default: `0.0`, `0.0`, `0.0` (degrees)
  + `poi_lever_arm`: The lever arm from the IMU reference point to a user-defined POI
    + Parameters `delta_x`,`delta_y` and `delta_z` refer to the vehicle reference frame
    + default: `0.0`, `0.0`, `0.0` (meters)
  + `ant_lever_arm`: The lever arm from the IMU reference point to the main GNSS antenna
    + The parameters `x`,`y` and `z` refer to the vehicle reference frame
    + default: `0.0`, `0.0`, `0.0` (meters)
  + `vsm_lever_arm`: The lever arm from the IMU reference point to the velocity sensor
    + The parameters `vsm_x`,`vsm_y` and `vsm_z` refer to the vehicle reference frame 
    + default: `0.0`, `0.0`, `0.0` (meters)
+ `ins_initial_heading`: How the receiver obtains the initial INS/GNSS integrated heading during the alignment phase
    + In case it is `auto`, the initial integrated heading is determined from GNSS measurements.
    + In case it is `stored`, the last known heading when the vehicle stopped before switching off the receiver is used as initial heading. Use if vehicle does not move when the receiver is switched off.
    + default: `auto`
+ `ins_std_dev_mask`: Maximum accepted error
  + `att_std_dev`: Configures an output limit on standard deviation of the attitude angles (max error accepted: 5 degrees)
  + `pos_std_dev`: Configures an output limit on standard deviation of the position (max error accepted: 100 meters)
  + default: `5` degrees, `10` meters    
+ `ins_use_poi`: Whether or not to use the POI defined in `ins_spatial_config.poi_lever_arm`
  + If true, the point at which the INS navigation solution (e.g. in `insnavgeod` ROS topic) is calculated will be the POI as defined above (`poi_frame_id`), otherwise it'll be the main GNSS antenna (`frame_id`). Has to be set to `true` if tf shall be published.
  + default: `true`
+ `ins_vsm`: Configuration of the velocity sensor measurements.
  + `ros`: VSM info received from ROS msgs
    + `source`: Specifies which ROS message type shall be used, options are `odometry` or `twist`. Accordingly, a subscriber is established of the type [`nav_msgs/Odometry.msg`](https://docs.ros2.org/foxy/api/nav_msgs/msg/Odometry.html) or [`geometry_msgs/TwistWithCovarianceStamped.msg`](https://docs.ros2.org/foxy/api/geometry_msgs/msg/TwistWithCovarianceStamped.html) listening on the topics `odometry_vsm` or `twist_vsm` respectively. Only linear velocities are evaluated. Measurements have to be with respect to the frame aligned with the vehicle and defined by `ins_spatial_config.vsm_lever_arm` or tf-frame `vsm_frame_id`, see also comment in [`nav_msgs/Odometry.msg`](https://docs.ros2.org/foxy/api/nav_msgs/msg/Odometry.html) that twist should be specified in `child_frame_id`.
      + default: ""
    + `config`: Defines which measurements belonging to the respective axes are forwarded to the INS. In addition, non-holonomic constraints may be introduced for directions known to be restricted in movement. For example, a vehicle with Ackermann steering is limited in its sidewards and upwards movement. So, even if only motion in x-direction may be measured, zero-velocities for y and z may be sent. Only has to be set if `ins_vsm.ros.source`is set to `odometry` or `twist`.
      + default: []
    + `variances_by_parameter`: Wether variances shall be entered by parameter `ins_vsm.ros.variances` or the values from inside the ROS messages are used. Only has to be set if `ins_vsm.source`is set to `odometry` or `twist`.
      + default: false
    + `variances`: Variances of the respective axes. Only have to be set if `ins_vsm.variances_by_parameter` is set to `true`. Values must be > 0.0, else measurements cannot not be used.
      + default: []
  + `ip_server`:
    + `id`: IP server to receive the VSM info (e.g. `IPS2`).
        + default: ""
    + `port`: TCP port to receive the VSM info. When selecting a port number, make sure to avoid conflicts with other services.
      + default: 0
    + `keep_open` determines wether this connections to receive VSM shall be kept open on driver shutdown. If set to `true` the Rx will still be able to use external VSM info to improve its localization.
      + default: `true`
  + `serial`:
    + `port`: Serial port to receive the VSM info.
      + default: ""
    + `baud_rate`: Baud rate of the serial port to receive the VSM info.
      + default: 115200
    + `keep_open` determines wether this connections to receive VSM shall be kept open on driver shutdown. If set to `true` the Rx will still be able to use external VSM info to improve its localization.
      + default: `true`

Logger

+ `activate_debug_log`: `true` if ROS logger level shall be set to debug.

  • Parameters Configuring (Non-)Publishing of ROS Messages

    NMEA/SBF Messages to be Published

    • publish.gpgga: true to publish nmea_msgs/GPGGA.msg messages into the topic /gpgga
    • publish.gprmc: true to publish nmea_msgs/GPRMC.msg messages into the topic /gprmc
    • publish.gpgsa: true to publish nmea_msgs/GPGSA.msg messages into the topic /gpgsa
    • publish.gpgsv: true to publish nmea_msgs/GPGSV.msg messages into the topic /gpgsv
    • publish.measepoch: true to publish septentrio_gnss_driver/MeasEpoch.msg messages into the topic /measepoch
    • publish.galauthstatus: true to publish septentrio_gnss_driver/GALAuthStatus.msg messages into the topic /galauthstatus and corresponding /diganostics
    • publish.aimplusstatus: true to publish septentrio_gnss_driver/RFStatus.msg messages into the topic /rfstatus, septentrio_gnss_driver/AIMPlusStatus.msg messages into /aimplusstatus and corresponding /diganostics. Some information is only available with active OSNMA.
    • publish.pvtcartesian: true to publish septentrio_gnss_driver/PVTCartesian.msg messages into the topic /pvtcartesian
    • publish.pvtgeodetic: true to publish septentrio_gnss_driver/PVTGeodetic.msg messages into the topic /pvtgeodetic
    • publish.basevectorcart: true to publish septentrio_gnss_driver/BaseVectorCart.msg messages into the topic /basevectorcart
    • publish.basevectorgeod: true to publish septentrio_gnss_driver/BaseVectorGeod.msg messages into the topic /basevectorgeod
    • publish.poscovcartesian: true to publish septentrio_gnss_driver/PosCovCartesian.msg messages into the topic /poscovcartesian
    • publish.poscovgeodetic: true to publish septentrio_gnss_driver/PosCovGeodetic.msg messages into the topic /poscovgeodetic
    • publish.velcovcartesian: true to publish septentrio_gnss_driver/VelCovCartesian.msg messages into the topic /velcovcartesian
    • publish.velcovgeodetic: true to publish septentrio_gnss_driver/VelCovGeodetic.msg messages into the topic /velcovgeodetic
    • publish.atteuler: true to publish septentrio_gnss_driver/AttEuler.msg messages into the topic /atteuler
    • publish.attcoveuler: true to publish septentrio_gnss_driver/AttCovEuler.msg messages into the topic /attcoveuler
    • publish.gpst: true to publish sensor_msgs/TimeReference.msg messages into the topic /gpst
    • publish.navsatfix: true to publish sensor_msgs/NavSatFix.msg messages into the topic /navsatfix
    • publish.gpsfix: true to publish gps_msgs/GPSFix.msg messages into the topic /gpsfix
    • publish.pose: true to publish geometry_msgs/PoseWithCovarianceStamped.msg messages into the topic /pose
    • publish.twist: true to publish geometry_msgs/TwistWithCovarianceStamped.msg messages into the topics /twist and /twist_ins respectively
    • publish.diagnostics: true to publish diagnostic_msgs/DiagnosticArray.msg messages into the topic /diagnostics
    • publish.insnavcart: true to publish septentrio_gnss_driver/INSNavCart.msg message into the topic/insnavcart
    • publish.insnavgeod: true to publish septentrio_gnss_driver/INSNavGeod.msg message into the topic/insnavgeod
    • publish.extsensormeas: true to publish septentrio_gnss_driver/ExtSensorMeas.msg message into the topic/extsensormeas
    • publish.imusetup: true to publish septentrio_gnss_driver/IMUSetup.msg message into the topic/imusetup
    • publish.velsensorsetup: true to publish septentrio_gnss_driver/VelSensorSetup.msgs message into the topic/velsensorsetup
    • publish.exteventinsnavcart: true to publish septentrio_gnss_driver/ExtEventINSNavCart.msgs message into the topic/exteventinsnavcart
    • publish.exteventinsnavgeod: true to publish septentrio_gnss_driver/ExtEventINSNavGeod.msgs message into the topic/exteventinsnavgeod
    • publish.imu: true to publish sensor_msgs/Imu.msg message into the topic/imu
    • publish.localization: true to publish nav_msgs/Odometry.msg message into the topic/localization
    • publish.tf: true to broadcast tf of localization. ins_use_poi must also be set to true to publish tf. Note that only one of publish.tf or publish.tf_ecef may be true.
    • publish.localization_ecef: true to publish nav_msgs/Odometry.msg message into the topic/localization related to ECEF frame.
    • publish.tf_ecef: true to broadcast tf of localization related to ECEF frame. ins_use_poi must also be set to true to publish tf. Note that only one of publish.tf or publish.tf_ecef may be true.

ROS Topic Publications

A selection of NMEA sentences, the majority being standardized sentences, and proprietary SBF blocks is translated into ROS messages, partly generic and partly custom, and can be published at the discretion of the user into the following ROS topics. All published ROS messages, even custom ones, start with a ROS generic header std_msgs/Header.msg, which includes the receiver time stamp as well as the frame ID, the latter being specified in the ROS parameter frame_id.

Available ROS Topics

  • /gpgga: publishes nmea_msgs/Gpgga.msg - converted from the NMEA sentence GGA.
  • /gprmc: publishes nmea_msgs/Gprmc.msg - converted from the NMEA sentence RMC.
  • /gpgsa: publishes nmea_msgs/Gpgsa.msg - converted from the NMEA sentence GSA.
  • /gpgsv: publishes nmea_msgs/Gpgsv.msg - converted from the NMEA sentence GSV.
  • /measepoch: publishes custom ROS message septentrio_gnss_driver/MeasEpoch.msg, corresponding to the SBF block MeasEpoch.
  • /galauthstatus: publishes custom ROS message septentrio_gnss_driver/GALAuthStatus.msg, corresponding to the SBF block GALAuthStatus.
  • /rfstatus: publishes custom ROS message septentrio_gnss_driver/RFStatus.msg, compiled from the SBF block RFStatus.
  • /aimplusstatus: publishes custom ROS message septentrio_gnss_driver/AIMPlusStatus.msg, reporting status of AIM+. Converted from SBF blocks RFStatus and optionally GALAuthStatus. For the latter OSNMA has to be activated.
  • /pvtcartesian: publishes custom ROS message septentrio_gnss_driver/PVTCartesian.msg, corresponding to the SBF block PVTCartesian (GNSS case) or INSNavGeod (INS case).
  • /pvtgeodetic: publishes custom ROS message septentrio_gnss_driver/PVTGeodetic.msg, corresponding to the SBF block PVTGeodetic (GNSS case) or INSNavGeod (INS case).
  • /basevectorcart: publishes custom ROS message septentrio_gnss_driver/BaseVectorCart.msg, corresponding to the SBF block BaseVectorCart.
  • /basevectorgeod: publishes custom ROS message septentrio_gnss_driver/BaseVectorGeod.msg, corresponding to the SBF block BaseVectorGeod.
  • /poscovcartesian: publishes custom ROS message septentrio_gnss_driver/PosCovCartesian.msg, corresponding to SBF block PosCovCartesian (GNSS case) or INSNavGeod (INS case).
  • /poscovgeodetic: publishes custom ROS message septentrio_gnss_driver/PosCovGeodetic.msg, corresponding to SBF block PosCovGeodetic (GNSS case) or INSNavGeod (INS case).
  • /velcovcartesian: publishes custom ROS message septentrio_gnss_driver/VelCovCartesian.msg, corresponding to SBF block VelCovCartesian (GNSS case).
  • /velcovgeodetic: publishes custom ROS message septentrio_gnss_driver/VelCovGeodetic.msg, corresponding to SBF block VelCovGeodetic (GNSS case).
  • /atteuler: publishes custom ROS message septentrio_gnss_driver/AttEuler.msg, corresponding to SBF block AttEuler.
  • /attcoveuler: publishes custom ROS message septentrio_gnss_driver/AttCovEuler.msg, corresponding to the SBF block AttCovEuler.
  • /gpst (for GPS Time): publishes generic ROS message sensor_msgs/TimeReference.msg, converted from the PVTGeodetic (GNSS case) or INSNavGeod (INS case) block's GPS time information, stored in its block header.
  • /navsatfix: publishes generic ROS message sensor_msgs/NavSatFix.msg, converted from the SBF blocks PVTGeodetic,PosCovGeodetic (GNSS case) or INSNavGeod (INS case)
  • /gpsfix: publishes generic ROS message gps_msgs/GPSFix.msg, which is much more detailed than sensor_msgs/NavSatFix.msg, converted from the SBF blocks PVTGeodetic, PosCovGeodetic, ChannelStatus, MeasEpoch, AttEuler, AttCovEuler, VelCovGeodetic, DOP (GNSS case) or INSNavGeod, DOP (INS case). In order to publish heading information, the field dip is diverted from its intended meaning an populated with the heading angle and err_dip with its uncertainty.
  • /pose: publishes generic ROS message geometry_msgs/PoseWithCovarianceStamped.msg, converted from the SBF blocks PVTGeodetic, PosCovGeodetic, AttEuler, AttCovEuler (GNSS case) or INSNavGeod (INS case).
    • Note that GNSS provides absolute positioning, while robots are often localized within a local level cartesian frame. The pose field of this ROS message contains position with respect to the absolute ENU frame (longitude, latitude, height), i.e. not a cartesian frame, while the orientation is with respect to a vehicle-fixed (e.g. for mosaic-x5 in moving base mode via the command setAttitudeOffset, ...) !local! NED frame or ENU frame if use_ros_axis_directions is set true. Thus the orientation is !not! given with respect to the same frame as the position is given in. The cross-covariances are hence set to 0.
  • /twist: publishes generic ROS message geometry_msgs/TwistWithCovarianceStamped.msg, converted from the SBF blocks PVTGeodetic and VelCovGeodetic.
  • /twist_ins: publishes generic ROS message geometry_msgs/TwistWithCovarianceStamped.msg, converted from SBF block INSNavGeod.
  • /insnavcart: publishes custom ROS message septentrio_gnss_driver/INSNavCart.msg, corresponding to SBF block INSNavCart
  • /insnavgeod: publishes custom ROS message septentrio_gnss_driver/INSNavGeod.msg, corresponding to SBF block INSNavGeod
  • /extsensormeas: publishes custom ROS message septentrio_gnss_driver/ExtSensorMeas.msg, corresponding to SBF block ExtSensorMeas.
  • /imusetup: publishes custom ROS message septentrio_gnss_driver/IMUSetup.msg, corresponding to SBF block IMUSetup.
  • /velsensorsetup: publishes custom ROS message septentrio_gnss_driver/VelSensorSetup.msg corresponding to SBF block VelSensorSetup.
  • /exteventinsnavcart: publishes custom ROS message septentrio_gnss_driver/INSNavCart.msg, corresponding to SBF block ExtEventINSNavCart.
  • /exteventinsnavgeod: publishes custom ROS message septentrio_gnss_driver/INSNavGeod.msg, corresponding to SBF block ExtEventINSNavGeod.
  • /diagnostics: accepts generic ROS message diagnostic_msgs/DiagnosticArray.msg, converted from the SBF blocks QualityInd, ReceiverStatus and ReceiverSetup
  • /imu: accepts generic ROS message sensor_msgs/Imu.msg, converted from the SBF blocks ExtSensorMeas and INSNavGeod.
    • The ROS message sensor_msgs/Imu.msg can be fed directly into the robot_localization of the ROS navigation stack. Note that use_ros_axis_orientation should be set to true to adhere to the ENU convention.
  • /localization: accepts generic ROS message nav_msgs/Odometry.msg, converted from the SBF block INSNavGeod and transformed to UTM.
    • The ROS message nav_msgs/Odometry.msg can be fed directly into the robot_localization of the ROS navigation stack. Note that use_ros_axis_orientation should be set to true to adhere to the ENU convention.
  • /localization_ecef: accepts generic ROS message nav_msgs/Odometry.msg, converted from the SBF blocks INSNavCart and INSNavGeod.
    • The ROS message nav_msgs/Odometry.msg can be fed directly into the robot_localization of the ROS navigation stack. Note that use_ros_axis_orientation should be set to true to adhere to the ENU convention.

Suggestions for Improvements

Some Ideas + Equip ROSaic with an NTRIP client such that it can forward corrections to the receiver independently of `Data Link`.

Adding New SBF Blocks or NMEA Sentences

Steps to Follow Is there an SBF or NMEA message that is not being addressed while being important to your application? If yes, follow these steps: 1. Find the log reference of interest in the publicly accessible, official documentation. Hence select the reference guide file, e.g. for mosaic-x5 in the [product support section for mosaic-X5](https://www.septentrio.com/en/support/mosaic/mosaic-x5), Chapter 4, of Septentrio's homepage. 2. SBF: Add a new `.msg` file to the `../msg` folder. And modify the `../CMakeLists.txt` file by adding a new entry to the `add_message_files` section. 3. Add msg header and typedef to `typedefs.hpp`. 4. Parsers: - SBF: Add a parser to the `sbf_blocks.hpp` file. - NMEA: Construct two new parsing files such as `gpgga.cpp` to the `../src/septentrio_gnss_driver/parsers/nmea_parsers` folder and one such as `gpgga.hpp` to the `../include/septentrio_gnss_driver/parsers/nmea_parsers` folder. 5. Processing the message/block: - SBF: Extend the `SbfId` enumeration in the `message_handler.hpp` file with a new entry. - SBF: Extend the SBF switch-case in `message_handler.cpp` file with a new case. - NMEA: Extend the `nmeaMap_` in the `message_handler.hpp` file with a new pair. - NMEA: Extend the NMEA switch-case in `message_handler.cpp` file with a new case. 6. Create a new `publish/..` ROSaic parameter in the `../config/rover.yaml` file and create a boolean variable `publish_xxx` in the struct in the `settings.h` file. Parse the parameter in the `rosaic_node.cpp` file. 7. Add SBF block or NMEA to data stream setup in `communication_core.cpp` (function `configureRx()`).
CHANGELOG

Changelog for package septentrio_gnss_driver

1.3.2 (2022-11-19) -----------* Merge pull request #106 from thomasemter/dev/next2 Fix IMU units * Fix topics namespace * Fix units of imu angular rates * Merge pull request #96 from septentrio-gnss/dev2 Dev2 * Contributors: Thomas Emter, Tibor Dome, septentrio-users

1.3.1 (2022-07-06)

  • New Features

    : - Recovery from connection interruption - Add option to bypass configuration of Rx - Add tests - OSNMA - Latency compensation for ROS timestamps - Output of SBf block VelCovCartesian - Support for UDP and TCP via IP server - New VSM handling allows for unknown variances (INS firmware >= 1.4.1) - Add heading angle to GPSFix msg (by diverting dip field, cf. readme)

  • Improvements

    : - Rework IO core and message handling - Unified stream processing - Internal data queue - Prevent message loss in file reading - Add some explanatory warnings for parameter mismatches - Add units to message definitions

  • Fixes

    : - navsatfix for INS - Empty headers - Single antenna receiver setup

  • Preliminary Features

    : - Output of localization and tf in ECEF frame, testing and feedback welcome

  • Commits

    : - Merge pull request #83 from thomasemter/dev/next2 Update readme - Add expected release dates - Add known issues to readme - Update version - Update readme - Merge pull request #82 from thomasemter/dev/next2 Fix spelling - Categorize stream params - Add keep alive check for TCP - Fix spelling - Add TCP communication via static IP server - Add units to msgs - Fix spelling - Merge pull request #76 from thomasemter/dev/next2 upcoming release - Add heading to GPSFix msg - Move constant - Change log level of firmware check - Add improved VSM handling - Change INS in GNSS node detection to auto - Fix invald v_x var case - Refine readme on UDP - Improve server duplicate check - Add more info un UDP configuration - Fix publish check - Add more publishing checks for configured Rx - Add const for max udp packet size - Update readme and changelog - Add device check to node - Fix param name separators - Add checks for IP server duplicates - Add latency compensation to att msgs - Add device check logic - Add UDP params and setup logic - Fix multi msg per packet - Fix localization stamp and tf publishing - Change VSM to be averaged and published with 2 Hz - Change VSM to be averaged and published with 2 Hz - Always publish raw IMU data as indicated - Change to empty fields - Refine diagnostics naming scheme and add trigger to ensure emission of ReceiverSetup - Change diagnostics naming scheme - Add missing new params to gnss.yaml - Expand readme on AIM+ - Reformulate readme about ROS and ROS2 - Add custom message to report AIM+ status - Catch invalid UTM conversion - Robustify command reset - Add RFStatus diagnostics - Add VelCovCartesian output - Refine Rx type check - Add option for latency compensation - Fix param type misinterpretation - Add OSNMA msg and diagnostics - Update changelog - Refine README and fix compiled message logic - Update changelog - Add warning for configuring INS as GNSS - Add warn log for misconfiguration - Fix pose publishing rate - Fix navsatfix publishing - Make vars const - Merge rework of internal IO handling - Change connection thread - Fix attitude cov flipped twice - Add cov alignment from true north to grid north - Rename meridian convergence and fix sense - Remove obsolete define - Add tests - Rename example launch files so they are found by auto-completion - Merge branch \'dev/ros2\' into dev/next2 - Fix lat/long in rad - Fix readme concerning ROS 2 distros - Reorder localization msg filling - Update readme - Fix NED to ECEF rotation matrix - Add localization ECEF publishing - Add ecef localization msg - Add local to ecef transforms - Contributors: Thomas Emter, Tibor Dome

1.2.3 (2022-11-09)

  • New Features

    : - Twist output option - Example config files for GNSS and INS - Get leap seconds from receiver - Firmware check - VSM from odometry or twist ROS messages - Add receiver type in case INS is used in GNSS mode - Add publishing of base vector topics

  • Improvements

    : - Rework RTK corrections parameters and improve flexibility

  • Fixes

    : - /tf not being published without /localization - Twist covariance matrix of localization - Support 5 ms period for IMU explicitly

1.2.2 (2022-06-22)

  • Fixes

    : - Memory corruption under adverse conditions

  • Commits

    : - Merge pull request #66 from thomasemter/dev/next2 Fix memory corruption - Fix parameter warnings - Reset buffer size to 16384 - Update changelog - Fix memory corruption - Replace maps with unordered_maps - Overload timestamp function - Fix frame ids for INS msgs - Add define to avoid usage of deprecated header - Change readme on gps-msgs packet - Add info on user credentials - Fix spelling in readme - Merge remote-tracking branch \'upstream/ros2\' into dev/next2 - Add comment for heading from pose - Contributors: Thomas Emter, Tibor Dome

1.2.1 (2022-05-16)

  • New Features

    : - Add login credentials - Activate NTP server if use_gnss_time is set to true

  • Improvements

    : - Add NED option to localization

  • Fixes

    : - IMU orientation for ROS axis convention

  • Commits

    : - Merge pull request #63 from thomasemter/dev/next2 Small fixes and additions - Merge pull request #60 from wep21/support-rolling fix: modify build error for rolling/humble - Revert change for deprecation warning in Humble - Change links to reflect ROS2 - Amend readme regarding robot_localization - Fix compiler warnings for humble - Add more explanations for IMU orientation in ROS convention - Fix formatting in readme - Fix package name in readme - Update readme - Update changelog - Fix IMU orientation for ROS axis orientation - Activate NTP only if GNSS time is used - Add NED option to localization - Set NMEA header to GP - Update readme and changelog - Activate NTP server - Add credentials for access control - fix: modify build error for rolling/humble - Contributors: Daisuke Nishimatsu, Thomas Emter, Tibor Dome

1.2.0 (2022-04-27)

  • New Features

    : - Add option to use ROS axis orientations according to REP103 - Add frame_id parameters - Add option to get frames from tf - Publishing of cartesian localization in UTM (topic and/or tf) for INS - Publishing of IMU topic for INS - Publishing of MeasEpoch - ROS2 branch

  • Improvements

    : - Add multi antenna option - Increase number of SBF streams - Add option to set polling_period to \"on change\" - Increased buffer size from 8192 to 131072 bytes - Add endianess aware parsers - Only publish topics set to true - Add parameter to switch DEBUG logging on and off - Change GPxxx messages to ROS built-in types - Remove duplicate INS msg types

  • Fixes

    : - Setting of antenna type - Publishing rate interconnections of gpsfix and velcovgeodetic - Missing quotes for antenna type - Broken attitude parsing pose and gpsfix from INS - IMU orientation was not sent to Rx - Graceful shutdown of threads

  • Commits

    : - Merge branch \'dev\' - Prepare new release - Prepare new release - Merge pull request #53 from thomasemter/dev/refactor Very last changes - Add geographic lib dependency to package.xml - Add comment for frame of main antenna - Move utm zone locking section in readme - Reformulate readme section on frames - Merge pull request #52 from thomasemter/dev/refactor Last changes - Change frame id back to poi_frame_id - Make error log more explicit - Merge pull request #49 from thomasemter/dev/refactor Improve IMU blocks sync and do-not-use value handling - Fix buffer size in changelog - Turn off Nagle\'s algorithm for TCP - Fix changelog formatting - Fix readme - Set default base frame to base_link - Fix valid tow check logic - Increase buffer size for extreme stress tests - Fix crc check - Fix and streamline tf handling - Add checks for validity of values - Fix rad vs deg - Update changelog - Add some comments - Set stdDevMask to values > 0.0 in node - Set stdDevMask to values > 0.0 - Add info on RNDIS and set it to default - Increase default serial baud rate - Add parameter to set log level to debug - Change defaults for publishers in node - Put publish params together and fix mismatch in readme - Improve IMU blocks sync and do-not-use value handling - Merge pull request #48 from thomasemter/dev/refactor Fix measepoch not publishing without gpsfix - Fix measepoch not publishing without gpsfix - Merge pull request #47 from thomasemter/dev/refactor Dev/refactor - Publish only messages set to true - Remove leftover declaration - Merge branch \'dev/endianess_agnostic\' into dev/refactor - Update readme to reflect endianess aware parsing - Remove msg smart pointers - Fix array assertion failure - Cleanup - Add ReceiverStatus parser - Add QualityInd parser - Add DOP parser - Add ReceiverSetup parser - Fix MeasEpoch and ChannelStatus parsers, add measepoch publishing - Add ChannelStatus parser - Add MeasEpoch parser - Add IMU and VelSensor setup parsers - Add Cov SBF parsers - Add templated qi parser function - Add AttEuler+Cov parser - Revert ordering change inside INSNav ROS msgs - Add ExtSensorMeas parser - Add PVT parsers - Add range checks to parsers - Replace INSNav grammar with parsers - Test parser vs. grammar for better performance - Fix sb_list check - Add IMU and VelSensor setup grammars - Move adapt ROS header to typedefs.h - Add revision check to MeasEpoch - Fix ReceiverStatus grammar - Extend ReceiverSetup and add revision checks - Change logger and fix loop range - Remove reserved bytes from parsing - Remove obsolete structs - Directly parse Cov SBFs to ROS msg - Directly parse PVT SBFs, remove obsolete ids - Rename rev to revision - Fix block header parsing - Directly parse AttEuler to ROS msg - Directly parse to ROS msgs for INSNavXxx - Exchange pow with square function and remove casts - Merge pull request #46 from thomasemter/dev/refactor Dev/refactor - Simplify sync bytes check - Move tow/wnc to BlockHeader - Adjust order in INSNav ros msgs - Fix INSNav grammars - Change BlockHeader structure - Remove length ref from header - Rectify sb_list check of INSNavXxx - Add automtatic activation of multi-antenna mode - Merge branch \'dev/refactor\' of https://github.com/thomasemter/septentrio_gnss_driver into dev/refactor - Add automtatic activation of multi-antenna mode - Fix wrong scope of phoenix::ref variables - Fix AttEuler grammar - Add max size checks to QualityInd and ReceiverStatus - Replace locals with phoenix::ref in grammars - Add revision dependent parsing to PVTs - Change offset check to epsilon - Change offset check to epsilon - Fix parsing checks - Set has arrived to false on parsing error - Add INSNav grammars - Add abs to offset check - Add abs to offset check - Add Cov grammars - Remove superfluous typdefs of structs - Add ReceiverStatus grammar - Add QualityINd grammar - Merge pull request #45 from thomasemter/dev/refactor Dev/refactor - Add id check to header grammar - Add id check to header grammar - Add ReceiverSetup grammar - Add DOP grammar - Directly intialize vector to parse - Add MeasEpoch grammar - Remove duplicate msg types - Remove obsolete include - Add revision and length return to header grammar - Merge branch \'feature/endianess_agnostic\' into dev/endianess_agnostic - Make multi_antenna option also usable for gnss - Add typedefs plus some minor changes - Add warning concerning pitch angle if antennas are rotated - Add multi antenna option to ins and fix antenna offset decimal places trimming - Fix identation - Distinguish between gnss and ins for spatial config from tf - Merge pull request #43 from thomasemter/dev/refactor Dev/refactor - Add vehicle frame for clarity - Handle missing tf more gently - Merge branch \'dev/spatial_config_via_tf\' into dev/refactor - Update readme - Fix antenna offset from tf - Add automatic publishing of localization if tf is activated - Add automatic publishing of localization if tf is activated - Add spatial config via tf, to be tested - Fix crashes due to parsing errors (replacing uncatched throws) - Add tf broadcasting - Add comments - Add localization in UTM output - Add check to IMU msg sync - Change msg sync to allow for 200 Hz IMU msgs - Add ROS IMU msg - Fix IMU setup message attitude conversion - Fix pose from INS data - Fix IMU raw data rotation compensation - Make antenna attitude offset usable by GNSS - Add ros directions option to pose and fix covariances - Update readme - Merge branch \'feature/ros_axis_orientation\' into dev/refactor - Add nmea_msgs dependencies - Merge branch \'dev/nmea\' into dev/refactor - Update readme - Update readme - Add antenna offsets to conversions - Fix IMU orientation conversion - Change ExtSensorMead temperature to deg C - Add axis orientation info to readme - Fix IMU axis orientation - Change get int param - Update readme to reflect removal of aux antenna offset - Fix different antenna setup message for INS and remove obsolete aux1 antenna offset for GNSS - Fix ExtSensorMeas message filling - Fix ExtSensorMeas message to reflect available fields - Fix missing INS blocks - Fix missing INS blocks - WIP, introduce ros axis orientation option, to be tested - Add option to set pvt rate to OnChange - Add comment on NTP to readme - Change to nmea_msgs - Add automatic addition of needed sub messages - Comment out setting debug level - Add comments and fix spelling errors - Merge pull request #42 from thomasemter/dev/refactor Dev/refactor - Change to quaternion msg typedef - Comment out debug logging - Remove filling of seq field - Change msg definitions to be compatible with ROS2 - Update readme - Change make_shared for portability and add more typedefs - Add get param int fallback for numeric antenna serial numbers - Change Attitude to be published with pvt rate - Add log identifier - Add checks for relevant ros params - Concatenate multiple SBF blocks in streams - Move main into own file - Move get ros time to AsyncManager - Remove obsolete param comment - Move get ros params to base class - Change to nsec timestamp internally - Add publishing functionality to node base class - Move node handle ptr and functions to base class and rename - Add stamp to nmea parsing - Add logging in PcapReader - Add logging in CircularBuffer - Add missed logging - Add logging in AsyncManager - Add getTime function - Add logging in RxMessage - Add logging in CallbackHandlers - Add log function to node by polymorphism, logging in Comm_OI - Fix wait function and force use_gnss_time when reading from file - Add thread shutdown and remove spurious delete - Add typedefs for ins messages - Add typedefs for gnss messages - Add typedefs for ros messages - Refine shutdown - Fix shutdown escalating to SIGTERM - Move waiting for response in send function - Make functions private - Change crc to C++ - Fix variable name - Remove global variables from node cpp file - Move more global settings to settings struct - Move more global settings to settings struct - Move global settings to settings struct - Move more functions to Comm_IO - Move settings to struct and configuration to Comm_IO - Merge branch \'dev/change_utc_calculation\' into dev/refactor - Remove obsolete global variables - Move g_unix_time to class - Make has_arrived booleans class memebers and rx_message a persistent class - Make node handle a class member - Fix parsing of ID and rev - Finish ChannelStatusGrammar, to be tested - WIP, partially fix ChannelStatusGrammar - Add SBF length parsing utility - Insert spirit parsers - WIP, add omission of padding bytes - WIP, add more spirit parsers - Add parsing utilities for tow, wnc and ID - Move getId/Tow/Wnc to parsing utilities - Change UTC calculation to use tow and wnc - WIP, add boost spirit and endian buffers - Change UTC calculation to use tow and wnc

  • ROS2 Commits

    : - Prepare ros2 release - Merge pull request #54 from thomasemter/dev/ros2 ROS2 branch - Port driver to ros2

  • Change UTC calculation to use tow and wnc

  • Contributors: Thomas Emter, Tibor Dome, tibordome

1.0.8 (2021-10-23)

  • Added INS Support

1.0.7 (2021-05-18)

  • Clang formatting, publishing from SBF log, play-back of PCAP files

1.0.6 (2020-10-16)

  • ROSaic binary installation now available on Melodic & Noetic

1.0.5 (2020-10-15)

  • changed repo name
  • v1.0.4
  • 1.0.3
  • Merge pull request #22 from septentrio-gnss/local_tibor New changelog
  • New changelog
  • Merge pull request #21 from septentrio-gnss/local_tibor Added rosdoc.yaml file
  • Merge pull request #20 from septentrio-gnss/local_tibor Improved doxygen annotations
  • Merge pull request #19 from septentrio-gnss/local_tibor Improved doxygen annotations
  • Update README.md
  • Merge pull request #18 from septentrio-gnss/local_tibor Adopted ROS and C++ conventions, added ROS diagnostics msg,
  • Update README.md
  • Update README.md
  • Update README.md
  • Contributors: septentrio-users, tibordome

1.0.4 (2020-10-11)

  • Added rosdoc.yaml file
  • Improved doxygen annotations
  • Improved doxygen annotations
  • Adopted ROS and C++ conventions, added ROS diagnostics msg, removed ROS garbage value bug, added auto-detection of SBF arrival order for composite ROS msgs
  • Merge branch \'master\' of https://github.com/septentrio-gnss/rosaic
  • NTRIP with Datalink, circular buffer, reading connection descriptor, new messages
  • Update README.md
  • Contributors: septentrio-users, tibordome

1.0.3 (2020-09-30)

  • Add new config/rover.yaml file
  • Add config/rover.yaml to .gitignore
  • Merge pull request #17 from septentrio-gnss/local_tibor NTRIP with Datalink, circular buffer, reading connection descriptor..
  • Merge branch \'local_tibor\'
  • NTRIP with Datalink, circular buffer, reading connection descriptor, new messages
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #16 from septentrio-gnss/local_tibor NTRIP parameters added, reconnect_delay_s implemented,
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #15 from tibordome/local_tibor GPSFix completed, datum as new parameter
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #14 from tibordome/local_tibor GPSFix completed, datum as new parameter
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #13 from tibordome/local_tibor Added AttCovEuler.msg and AttEuler.msg
  • Merge pull request #12 from tibordome/local_tibor Fixed service field of NavSatStatus
  • Contributors: Tibor Dome, septentrio-users, tibordome

1.0.2 (2020-09-25)

  • NTRIP parameters added, reconnect_delay_s implemented, package.xml updated, ROSaic now detects connection descriptor automatically, mosaic serial port parameter added
  • GPSFix completed, datum as new parameter, ANT type and marker-to-arp distances as new parameters, BlockLength() method corrected, sending multiple commands to Rx corrected by means of mutex
  • Contributors: tibordome

1.0.1 (2020-09-22)

  • GPSFix completed, datum as new parameter, ANT type and marker-to-arp distances as new parameters, BlockLength() method corrected, sending multiple commands to Rx corrected by means of mutex
  • Added AttCovEuler.msg and AttEuler.msg
  • Fixed service field of NavSatStatus, fixed ROS header\'s seq field of each published ROS message, added write method for sending commands to Rx, successfully tested, added AttEuler, added AttCovEuler
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #11 from tibordome/local_tibor rosconsole_backend_interface dependency not needed
  • rosconsole_backend_interface dependency not needed
  • Merge pull request #10 from tibordome/local_tibor rosconsole_log4cxx dep not needed
  • rosconsole_log4cxx dep not needed
  • Merge pull request #9 from tibordome/local_tibor rosconsole_log4cxx dep not needed
  • rosconsole_log4cxx dep not needed
  • Merge pull request #8 from tibordome/local_tibor Local tibor
  • Update README.md
  • Merge pull request #7 from tibordome/local_tibor Ready for First Release
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #6 from tibordome/local_tibor Local tibor
  • Merge pull request #5 from tibordome/local_tibor TCP seems to work
  • Contributors: Tibor Dome, tibordome

1.0.0 (2020-09-11)

  • Ready for first release
  • Added Gpgga.msg and PosCovGeodetic.msg files
  • Ready for First Release
  • Ready for first release
  • Ready for first release
  • Ready for first release
  • TCP bug removed
  • TCP bug removed
  • TCP seems to work
  • Merge pull request #4 from tibordome/v0.2 V0.2
  • PVTCartesian and PVTGeodetic publishing works on serial
  • PVTCartesian and PVTGeodetic publishing works on serial
  • Merge pull request #3 from tibordome/v0.2 Add doxygen_out and Doxyfile 2nd trial
  • Add doxygen_out and Doxyfile 2nd trial
  • Merge pull request #2 from tibordome/v0.1 Add doxygen_out and Doxyfile
  • Add doxygen_out and Doxyfile
  • Update README.md
  • Create README.md
  • Update LICENSE
  • Merge pull request #1 from tibordome/add-license-1 Create LICENSE
  • Create LICENSE
  • Create LICENSE
  • Commit
  • Successfully tested publishing to /gpgga topic via serial
  • To make sure master branch exists
  • Contributors: Tibor Dome, tibordome

Wiki Tutorials

See ROS Wiki Tutorials for more details.

Source Tutorials

Not currently indexed.

Recent questions tagged septentrio_gnss_driver at Robotics Stack Exchange

septentrio_gnss_driver package from septentrio_gnss_driver repo

septentrio_gnss_driver

Package Summary

Tags No category tags.
Version 1.3.2
License BSD 3-Clause License
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/septentrio-gnss/septentrio_gnss_driver.git
VCS Type git
VCS Version ros2
Last Updated 2023-11-22
Dev Status MAINTAINED
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

ROSaic: C++ driver for Septentrio's mosaic receivers and beyond

Additional Links

Maintainers

  • Tibor Dome
  • Septentrio

Authors

  • Tibor Dome

ROSaic = ROS + mosaic

Overview

This repository hosts drivers for ROS (Melodic and Noetic) and ROS 2 (Foxy, Galactic, Humble, Rolling, and beyond) - written in C++ - that work with mosaic and AsteRx - two of Septentrio's cutting-edge GNSS and GNSS/INS receiver families - and beyond. The ROS 2 version is available in this branch, whereas the ROS 1 version is available in the branch master.

Main Features: - Supports Septentrio's single antenna GNSS, dual antenna GNSS and INS receivers - Supports serial, TCP/IP and USB connections, the latter being compatible with both serial (RNDIS) and TCP/IP protocols - Supports several ASCII (including key NMEA ones) messages and SBF (Septentrio Binary Format) blocks - Reports status of AIM+ (Advanced Interference Mitigation including OSNMA) anti-jamming and anti-spoofing. - Can publish nav_msgs/Odometry message for INS receivers - Can blend SBF blocks PVTGeodetic, PosCovGeodetic, ChannelStatus, MeasEpoch, AttEuler, AttCovEuler, VelCovGeodetic and DOP in order to publish gps_common/GPSFix and sensor_msgs/NavSatFix messages - Supports axis convention conversion as Septentrio follows the NED convention, whereas ROS is ENU. - Easy configuration of multiple RTK corrections simultaneously (via NTRIP, TCP/IP stream, or serial) - Can play back PCAP capture logs for testing purposes - Tested with the mosaic-X5, mosaic-H, AsteRx-m3 Pro+ and the AsteRx-SBi3 Pro receiver - Easy to add support for more log types

Please let the maintainers know of your success or failure in using the driver with other devices so we can update this page appropriately.

Dependencies

The ros2 branch for this driver functions on ROS Foxy, Galactic, Rolling, and Humble (Ubuntu 20.04 or 22.04 respectively). It is thus necessary to install the ROS version that has been designed for your Linux distro.

Additional ROS packages have to be installed for the NMEA and GPSFix messages.

sudo apt install ros-$ROS_DISTRO-nmea-msgs ros-$ROS_DISTRO-gps-msgs.

The serial and TCP/IP communication interface of the ROS driver is established by means of the Boost C++ library. In the unlikely event that the below installation instructions fail to install Boost on the fly, please install the Boost libraries via

sudo apt install libboost-all-dev.

Compatiblity with PCAP captures are incorporated through pcap libraries. Install the necessary headers via

sudo apt install libpcap-dev.

Conversions from LLA to UTM are incorporated through GeographicLib. Install the necessary headers via

sudo apt install libgeographic-dev

Usage

Binary Install The binary release is now available for Foxy and Galactic. To install the binary package, simply run `sudo apt-get install ros-$ROS_DISTRO-septentrio-gnss-driver`.
Build from Source The package has to be built from source using [`colcon`](https://docs.ros.org/en/humble/Tutorials/Beginner-Client-Libraries/Colcon-Tutorial.html): ``` source /opt/ros/${ROS_DISTRO}/setup.bash # In case you do not use the default shell of Ubuntu, you need to source another script, e.g. setup.sh. mkdir -p ~/septentrio/src # Note: Change accordingly depending on where you want your package to be installed. cd ~/septentrio/src git clone https://github.com/septentrio-gnss/septentrio_gnss_driver git checkout ros2 # Install mentioned dependencies (`sudo apt install ros-$ROS_DISTRO-nmea_msgs ros-$ROS_DISTRO-gps-msgs libboost-all-dev libpcap-dev libgeographic-dev`) colcon build --packages-up-to septentrio_gnss_driver # Be sure to call colcon build in the root folder of your workspace. Launch files are installed, so changing them on the fly in the source folder only works with installing by symlinks: add `--symlink-install` echo "source ~/septentrio/devel/setup.bash" >> ~/.bashrc # It is convenient if the ROS environment variable is automatically added to your bash session every time a new shell is launched. Again, this works for bash shells only. Also note that if you have more than one ROS distribution installed, ~/.bashrc must only source the setup.bash for the version you are currently using. source ~/.bashrc ``` Run tests ``` colcon test --packages-select septentrio_gnss_driver --event-handlers console_direct+ ```
Notes Before Usage + In your bash sessions, navigating to the ROSaic package can be achieved from anywhere with no more effort than `roscd septentrio_gnss_driver`. + The driver assumes that our anonymous access to the Rx grants us full control rights. This should be the case by default, and can otherwise be changed with the `setDefaultAccessLevel` command. If user control is in place user credentials can be given by parameters `login.user` and `login.password`. + ROSaic only works from C++17 onwards due to std::any() etc. + Note for setting hw_flow_control: This is a string parameter, setting it to off without quotes leads to the fact that it is not read in correctly. + Note for setting ant_(aux1)_serial_nr: This is a string parameter, numeric only serial numbers should be put in quotes. If this is not done a warning will be issued and the driver tries to parse it as integer. + Once the colcon build or binary installation is finished, adapt the `config/rover.yaml` file according to your needs or assemble a new one. Launch as composition with `ros2 launch septentrio_gnss_driver rover.launch.py` to use `rover.yaml` or add `file_name:=xxx.yaml` to use a custom config. Alternatively launch as node with `ros2 launch septentrio_gnss_driver rover_node.launch.py` to use `rover_node.yaml` or add `file_name:=xxx.yaml` to use a custom config. Specify the communication parameters, the ROS messages to be published, the frequency at which the latter should happen etc. + Besides the aforementioned config file `rover.yaml` containing all parameters, specialized launch files for GNSS `config/gnss.yaml` and INS `config/ins.yaml` respectively contain only the relevant parameters in each case. - NOTE: Unless `configure_rx` is set to `false`, this driver will overwrite the previous values of the parameters, even if the value is left to zero in the "yaml" file. + The driver was developed and tested with firmware versions >= 4.10.0 for GNSS and >= 1.3.2 for INS. Receivers with older firmware versions are supported but some features may not be available. Known limitations are: * GNSS with firmware < 4.10.0 does not support IP over USB. * GNSS with firmware < 4.12.1 does not support OSNMA. * INS with firmware < 1.3.2 does not support NTP. * INS with firmware < 1.4 does not support OSNMA. * INS with firmware < 1.4.1 does not support improved VSM handling allowing for unknown variances. * INS with firmware 1.2.0 does not support velocity aiding. * INS with firmware 1.2.0 does not support setting of initial heading. + Known issues: * UDP over USB: Blocks are sent twice on GNSS with firmware <= 4.12.1 and INS with firmware <= 1.4. For GNSS it is fixed in version 4.14 (released on June 15th 2023), for INS it will be fixed in to-be-released 1.4.1 (expected in November 2023). + If `use_ros_axis_orientation` to `true` axis orientations are converted by the driver between NED (Septentrio: yaw = 0 is north, positive clockwise) and ENU (ROS: yaw = 0 is east, positive counterclockwise). There is no conversion when setting this parameter to `false` and the angles will be consistent with the web GUI in this case. :
``` # Example configuration Settings for the Rover Rx device: tcp://192.168.3.1:28784 serial: baudrate: 921600 hw_flow_control: "off" tcp: ip_server: "" port: 0 udp: ip_server: "" port: 0 unicast_ip: "" configure_rx: true login: user: "" password: "" osnma: mode: "off" ntp_server: "" keep_open: true frame_id: gnss imu_frame_id: imu poi_frame_id: base_link vsm_frame_id: vsm aux1_frame_id: aux1 vehicle_frame_id: base_link insert_local_frame: false local_frame_id: odom get_spatial_config_from_tf: true lock_utm_zone: true use_ros_axis_orientation: true receiver_type: gnss datum: Default poi_to_arp: delta_e: 0.0 delta_n: 0.0 delta_u: 0.0 att_offset: heading: 0.0 pitch: 0.0 ant_type: Unknown ant_aux1_type: Unknown ant_serial_nr: Unknown ant_aux1_serial_nr: Unknown leap_seconds: 18 polling_period: pvt: 500 rest: 500 use_gnss_time: false latency_compensation: false rtk_settings: ntrip_1: id: "NTR1" caster: "1.2.3.4" caster_port: 2101 username: "Asterix" password: "password" mountpoint: "mtpt1" version: "v2" tls: true fingerprint: "AA:BB:56:78:90:12: ... 78:90:12:34" rtk_standard: "RTCMv3" send_gga: "auto" keep_open: true ntrip_2: id: "NTR3" caster: "5.6.7.8" caster_port: 2101 username: "Obelix" password: "password" mountpoint: "mtpt2" version: "v2" tls: false fingerprint: "" rtk_standard: "RTCMv2" send_gga: "auto" keep_open: true ip_server_1: id: "IPS3" port: 28785 rtk_standard: "RTCMv2" send_gga: "auto" keep_open: true ip_server_2: id: "IPS5" port: 28786 rtk_standard: "CMRv2" send_gga: "auto" keep_open: true serial_1: port: "COM1" baud_rate: 230400 rtk_standard: "auto" send_gga: "sec1" keep_open: true serial_2: port: "COM2" baud_rate: 230400 rtk_standard: "auto" send_gga: "off" keep_open: true publish: # For both GNSS and INS Rxs navsatfix: false gpsfix: true gpgga: false gprmc: false gpst: false measepoch: false pvtcartesian: false pvtgeodetic: true basevectorcart: false basevectorgeod: false poscovcartesian: false poscovgeodetic: true velcovcartesian: false velcovgeodetic: false atteuler: true attcoveuler: true pose: false twist: false diagnostics: false aimplusstatus: true galauthstatus: false # For GNSS Rx only gpgsa: false gpgsv: false # For INS Rx only insnavcart: false insnavgeod: false extsensormeas: false imusetup: false velsensorsetup: false exteventinsnavcart: false exteventinsnavgeod: false imu: false localization: false tf: false localization_ecef: false tf_ecef: false # INS-Specific Parameters ins_spatial_config: imu_orientation: theta_x: 0.0 theta_y: 0.0 theta_z: 0.0 poi_lever_arm: delta_x: 0.0 delta_y: 0.0 delta_z: 0.0 ant_lever_arm: x: 0.0 y: 0.0 z: 0.0 vsm_lever_arm: vsm_x: 0.0 vsm_y: 0.0 vsm_z: 0.0 ins_initial_heading: auto ins_std_dev_mask: att_std_dev: 5.0 pos_std_dev: 10.0 ins_use_poi: true ins_vsm: source: "twist" config: [true, false, false] variances_by_parameter: true variances: [0.1, 0.0, 0.0] ip_server: id: "IPS2" port: 28787 keep_open: true serial: port: "COM3" baud_rate: 115200 keep_open: true # Logger activate_debug_log: false ``` In order to launch ROSaic, one must specify all `arg` fields of the `rover.py` file which have no associated default values, i.e. for now only the `file_name` field. Hence, the launch command reads `ros2 launch septentrio_gnss_driver rover.py file_name:=rover.yaml`. If multiple port are utilized for RTK corrections and/or VSM, which shall be closed after driver shutdown (`keep_open: false`), make sure to give the driver enough time to gracefully shutdown as closing the ports takes a few seconds. This can be accomplished in the launch files by increasing the timeout of SIGTERM (e.g. `sigterm_timeout = '10',`), see example launch files`rover.py`and `rover_node.py` respectively.

Inertial Navigation System (INS): Basics

  • An Inertial Navigation System (INS) is a device which takes the rotation and acceleration solutions as obtained from its Inertial Measurement Unit (IMU) and combines those with position and velocity information from the GNSS module. Compared to a GNSS system with 7D or 8D (dual-antenna systems) phase space solutions, the combined, Kalman-filtered 9D phase space solution (3 for position, 3 for velocity, 3 for orientation) of an INS is more accurate, more precise and more stable against GNSS outages.
  • The IMU is typically made up of a 3-axis accelerometer, a 3-axis gyroscope and sometimes a 3-axis magnetometer and measures the system's angular rate and acceleration.

    Measure and Compensate for IMU-Antenna Lever Arm

    • The IMU-antenna lever-arm is the relative position between the IMU reference point and the GNSS Antenna Reference Point (ARP), measured in the vehicle frame.
    • In case of AsteRx SBi3, the IMU reference point is clearly marked on the top panel of the receiver. It is important to compensate for the effect of the lever arm, otherwise the receiver may not be able to calculate an accurate INS position.
    • The IMU/antenna position can be changed by specifying the lever arm's x,yand z parameters in the config.yaml file under the ins_spatial_config.ant_lever_arm parameter.

    Screenshot from 2021-08-03 09-23-19 (1)

    Compensate for IMU Orientation + It is important to take into consideration the mounting direction of the IMU in the body frame of the vehicle. For e.g. when the receiver is installed horizontally with the front panel facing the direction of travel, we must compensate for the IMU’s orientation to make sure the IMU reference frame is aligned with the vehicle reference frame. The IMU position and orientation is printed on the top panel, cf. image below. + The IMU's orientation can be changed by specifying the orientation angles theta_x,theta_yand theta_z in the config.yaml file under ins_spatial_config.imu_orientation + The below image illustrates the orientation of the IMU reference frame with the associated IMU orientation for the depicted installation. Note that for use_ros_axis_orientation: true sensor_default is the top left position.

    Capture (1)

  • These Steps should be followed to configure the receiver in INS integration mode:

    • Specify receiver_type: INS
    • Specify the orientation of the IMU sensor with respect to your vehicle, using the ins_spatial_config.imu_orientation parameter.
    • Specify the IMU-antenna lever arm in the vehicle reference frame. This is the vector starting from the IMU reference point to the ARP of the main GNSS antenna. This can be done by means of the ins_spatial_config.ant_lever_arm parameter.
    • Specify ins_spatial_config.vsm_lever_arm if measurements of a velocity sensor is available.
    • Alternatively the lever arms may be specified via tf. Set get_spatial_config_from_tfto true in this case.
    • If the point of interest is neither the IMU nor the ARP of the main GNSS antenna, the vector between the IMU and the point of interest can be provided with the ins_solution/poi_lever_arm parameter.
  • For further more information about Septentrio receivers, visit Septentrio support resources or check out the user manual and reference guide of the AsteRx SBi3 receiver.

ROSaic Parameters

The following is a list of ROSaic parameters found in the config/rover.yaml file. * Parameters Configuring Communication Ports and Processing of GNSS and INS Data

Connectivity Specs

  • device: location of main device connection. This interface will be used for setup communication and VSM data for INS. Incoming data streams of SBF blocks and NMEA sentences are recevied either via this interface or a static IP server for TCP and/or UDP. The former will be utilized if section stream_device.tcp and stream_device.udp are not configured.
    • serial:xxx format for serial connections,where xxx is the device node, e.g. serial:/dev/ttyS0. If using serial over USB, it is recommended to specify the port by ID as the Rx may get a different ttyXXX on reconnection, e.g. serial:/dev/serial/by-id/usb-Septentrio_Septentrio_USB_Device_xyz.
    • file_name:path/to/file.sbf format for publishing from an SBF log
    • file_name:path/to/file.pcap format for publishing from PCAP capture.
      • Regarding the file path, ROS_HOME=`pwd` in front of roslaunch septentrio... might be useful to specify that the node should be started using the executable's directory as its working-directory.
    • tcp://host:port format for TCP/IP connections
      • 28784 should be used as the default (command) port for TCP/IP connections. If another port is specified, the receiver needs to be (re-)configured via the Web Interface before ROSaic can be used.
      • An RNDIS IP interface is provided via USB, assigning the address 192.168.3.1 to the receiver. This should work on most modern Linux distributions. To verify successful connection, open a web browser to access the web interface of the receiver using the IP address 192.168.3.1.
    • default: tcp://192.168.3.1:28784
  • serial: specifications for serial communication
    • baudrate: serial baud rate to be used in a serial connection. Ensure the provided rate is sufficient for the chosen SBF blocks. For example, activating MeasEpoch (also necessary for /gpsfix) may require up to almost 400 kBit/s.
    • rx_serial_port: determines to which (virtual) serial port of the Rx we want to get connected to, e.g. USB1 or COM1
    • hw_flow_control: specifies whether the serial (the Rx's COM ports, not USB1 or USB2) connection to the Rx should have UART hardware flow control enabled or not
      • off to disable UART hardware flow control, RTS|CTS to enable it
    • default: 921600, USB1, off
  • stream_device: If left unconfigured, by default device is utilized for the data streams. Within stream_device static IP servers may be defined instead. In config mode (configure_rx set to true), TCP will be prioritized over UDP. If Rx is pre-configured, both may be set simultaneously.
    • tcp: specifications for static TCP server of SBF blocks and NMEA sentences.
      • ip_server: IP server of Rx to be used, e.g. “IPS1”.
      • port: UDP destination port.
    • udp: specifications for low latency UDP reception of SBF blocks and NMEA sentences.
      • ip_server: IP server of Rx to be used, e.g. “IPS1”.
      • port: UDP destination port.
      • unicast_ip: Set to computer's IP to use unicast (optional). If not set multicast will be used.
  • login: credentials for user authentication to perform actions not allowed to anonymous users. Leave empty for anonymous access.
    • user: user name
    • password: password

OSNMA

  • osnma: Configuration of the Open Service Navigation Message Authentication (OSNMA) feature.
    • mode: Three operating modes are supported: off where OSNMA authentication is disabled, loose where satellites are included in the PVT if they are successfully authenticated or if their authentication status is unknown, and strict where only successfully-authenticated satellites are included in the PVT. In case of strict synchronization via NTP is mandatory.
      • default: off
    • ntp_server: In strict mode, OSNMA authentication requires the availability of external time information. In loose mode, this is optional but recommended for enhanced security. The receiver can connect to an NTP time server for this purpose. Options are default to let the receiver choose an NTP server or specify one like pool.ntp.org for example.
      • default: ""
    • keep_open: Wether OSNMA shall be kept active on driver shutdown.
      • default: true

Receiver Configuration

+ configure_rx: Wether to configure the Rx according to the config file. If set to `false`, the Rx has to be configured via the web interface and the settings must be saved. On the driver side communication has to set accordingly to serial, TCP or UDP (TCP and UDP may even be used simultaneously in this case). For TCP communication it is recommended to use a static TCP server (`stream_device.tcp.ip_server` and `stream_device.tcp.port`), since dynamic connections (`device` is tcp) are not guaranteed to have the same id on reconnection. It should also be ensured that obligatory SBF blocks are activated (as of now: ReceiverTime if `use_gnss_time` is set to `true`; `PVTGeodetic`or `PVTCartesian` if latency compensation for PVT related blocks shall be used). Further, if ROS messages compiled from multiple SBF blocks, it should be ensured that all necessary blocks are activated with matching periods, details can be found in section [ROS Topic Publications](#ros-topic-publications). The messages that shall be published still have to be set to `true` in the *NMEA/SBF Messages to be Published* section. Also, parameters concerning the connection and node setup are still relevant (sections: *Connectivity Specs*, *receiver type*, *Frame IDs*, *UTM Zone Locking*, *Time Systems*, *Logger*).
  + default: true

Receiver Type

  • receiver_type: This parameter is to select the type of the Septentrio receiver
    • gnss for GNSS receivers.
    • ins for INS receivers.
    • default: gnss
  • multi_antenna: Whether or not the Rx has multiple antennas.
    • default: false

Frame IDs

  • frame_id: name of the ROS tf frame for the Rx, placed in the header of published GNSS messages. It corresponds to the frame of the main antenna.
    • In ROS, the tf package lets you keep track of multiple coordinate frames over time. The frame ID will be resolved by tf_prefix if defined. If a ROS message has a header (all of those we publish do), the frame ID can be found via rostopic echo /topic, where /topic is the topic into which the message is being published.
    • default: gnss
  • imu_frame_id: name of the ROS tf frame for the IMU, placed in the header of published IMU message
    • default: imu
  • poi_frame_id: name of the ROS tf frame for the POI, placed in the child frame_id of localization if ins_use_poi is set to true.
    • default: base_link
  • vsm_frame_id: name of the ROS tf frame for the velocity sensor.
    • default: vsm
  • aux1_frame_id: name of the ROS tf frame for the aux1 antenna.
    • default: aux1
  • vehicle_frame_id: name of the ROS tf frame for the vehicle. Default is the same as poi_frame_id but may be set otherwise.
    • default: base_link
  • local_frame_id: name of the ROS tf frame for the local frame.
    • default: odom
  • insert_local_frame: Wether to insert a local frame to published tf according to ROS REP 105. The transform from the local frame specified by local_frame_id to the vehicle frame specified by vehicle_frame_id has to be provided, e.g. by odometry. Insertion of the local frame means the transform between local frame and global frame is published instead of transform between vehicle frame and global frame.
    • default: false
  • get_spatial_config_from_tf: wether to get the spatial config via tf with the above mentioned frame ids. This will override spatial settings of the config file. For receiver type ins with multi_antenna set to true all frames have to be provided, with multi_antenna set to false, aux1_frame_id is not necessary. For type gnss with dual-antenna setup only frame_id, aux1_frame_id, and poi_frame_id are needed. For single-antenna gnss no frames are needed. Keep in mind that tf has a tree structure. Thus, poi_frame_id is the base for all mentioned frames.
    • default: false
  • use_ros_axis_orientation Wether to use ROS axis orientations according to ROS REP 103 for body related frames and geographic frames. Body frame directions affect INS lever arms and IMU orientation setup parameters. Geographic frame directions affect orientation Euler angles for INS+GNSS and attitude of dual-antenna GNSS. If use_ros_axis_orientation is set to true, the driver converts between the NED convention (Septentrio: yaw = 0 is north, positive clockwise), and ENU convention (ROS: yaw = 0 is east, positive counterclockwise). There is no conversion when setting this parameter to false and the angles will be consistent with the web GUI in this case.
    • If set to false Septentrios definition is used, i.e., front-right-down body related frames and NED (north-east-down) for orientation frames.
    • If set to true ROS definition is used, i.e., front-left-up body related frames and ENU (east-north-up) for orientation frames.
    • default: true

UTM zone locking + lock_utm_zone: wether the UTM zone of the initial localization is locked, i.e., this zone is kept even if a zone transition would occur. + default: true

Datum

  • datum: With this command, the datum the coordinates should refer to is selected. With setting it to Default, the datum depends on the positioning mode, e.g. WGS84 for standalone positioning.
    • Since the standardized GGA message does only provide the orthometric height (= MSL height = distance from Earth's surface to geoid) and the geoid undulation (distance from geoid to ellipsoid) for which non-WGS84 datums cannot be specified, it does not affect the GGA message.
    • default: Default

POI-ARP Offset

+ `poi_to_arp`: offsets of the main GNSS antenna reference point (ARP) with respect to the point of interest (POI = marker). Use for static receivers only.
+ The parameters `delta_e`, `delta_n` and `delta_u` are the offsets in the East, North and Up (ENU) directions respectively, expressed in meters.
+ All absolute positions reported by the receiver are POI positions, obtained by subtracting this offset from the ARP. The purpose is to take into account the fact that the antenna may not be located directly on the surveying POI.
+ default: `0.0`, `0.0` and `0.0`

Antenna Attitude Offset

+ `att_offset`: Angular offset between two antennas (Main and Aux) and vehicle frame
+ `heading`: The perpendicular (azimuth) axis can be compensated for by adjusting the `heading` parameter
+ `pitch`: Vertical (elevation) offset can be compensated for by adjusting the `pitch` parameter
+ default: `0.0`, `0.0` (degrees)

Antenna Specs

  • ant_type: type of your main GNSS antenna
    • For best positional accuracy, it is recommended to select a type from the list returned by the command lstAntennaInfo, Overview. This is the list of antennas for which the receiver can compensate for phase center variation.
    • By default and if ant_type does not match any entry in the list returned by lstAntennaInfo, Overview, the receiver will assume that the phase center variation is zero at all elevations and frequency bands, and the position will not be as accurate.
    • default: Unknown
  • ant_serial_nr: serial number of your main GNSS antenna
  • ant_aux1_type and ant_aux1_serial_nr: same for Aux1 antenna

Leap Seconds

  • leap_seconds: Leap seconds are automatically gathered from the receiver via the SBF block ReceiverTime. If a log file is used for simulation and this block was not recorded, the number of leap seconds that have been inserted up until the point of ROSaic usage can be set by this parameter.
    • At the time of writing the code (2020), the GPS time, which is unaffected by leap seconds, was ahead of UTC time by 18 leap seconds. Adapt the leap_seconds parameter accordingly as soon as the next leap second is inserted into the UTC time or in case you are using ROSaic for the purpose of simulations.

Polling Periods

  • polling_period.pvt: desired period in milliseconds between the polling of two consecutive PVTGeodetic, PosCovGeodetic, PVTCartesian and PosCovCartesian blocks and - if published - between the publishing of two of the corresponding ROS messages (e.g. septentrio_gnss_driver/PVTGeodetic.msg). Consult firmware manual for allowed periods. If the period is set to a lower value than the receiver is capable of, it will be published with the next higher period. If set to 0, the SBF blocks are output at their natural renewal rate (OnChange).
  • polling_period.rest: desired period in milliseconds between the polling of all other SBF blocks and NMEA sentences not addressed by the previous parameter, and - if published - between the publishing of all other ROS messages
    • default: 500 (2 Hz)

Time Systems

  • use_gnss_time: true if the ROS message headers' unix epoch time field shall be constructed from the TOW/WNC (in the SBF case) and UTC (in the NMEA case) data, false if those times shall be taken by the driver from ROS time. If use_gnss_time is set to true, make sure the ROS system is synchronized to an NTP time server either via internet or ideally via the Septentrio receiver since the latter serves as a Stratum 1 time server not dependent on an internet connection. The NTP server of the receiver is automatically activated on the Septentrio receiver (for INS/GNSS a firmware >= 1.3.3 is needed).
    • default: true
  • latency_compensation: Rx reports processing latency in PVT and INS blocks. If set to truethis latency is subtracted from ROS timestamps in related blocks (i.e., use_gnss_time set to false). Related blocks are INS, PVT, Covariances, and BaseVectors. In case of use_gnss_time set to true, the latency is already compensated within the RX and included in the reported timestamps.
    • default: false

RTK corrections

  • rtk_settings: determines RTK connection parameters
    • There are multiple possibilities to feed RTK corrections to the Rx. They may be set simultaneously and the Rx will choose the nearest source.
      • a) ntrip_# if the Rx has internet access and is able to receieve NTRIP streams from a caster. Up to three NTRIP connections are possible.
      • b) ip_server_# if corrections are to be receieved via TCP/IP for example over Data Link from Septentrio's RxTools is installed on a computer. Up to five IP server connections are possible.
      • c) serial_# if corrections are to be receieved via a serial port for example over radio link from a local RTK base or over Data Link from Septentrio's RxTools installed on a computer. Up to five serial connections are possible.
    • ntrip_#: for receiving corretions from an NTRIP caster (# is from 1 ... 3).
      • id: NTRIP connection NTR1, NTR2, or NTR3.
      • default: ""
      • caster: is the hostname or IP address of the NTRIP caster to connect to.
      • default: ""
      • caster_port: IP port of the NTRIP caster.
      • default: 2021
      • username: user name for the NTRIP caster.
      • default: ""
      • pasword: password for the NTRIP caster. The receiver encrypts the password so that it cannot be read back with the command "getNtripSettings".
      • default: ""
      • mountpoint: mount point of the NTRP caster to be used.
      • default: ""
      • version: argument specifies which version of the NTRIP protocol to use (v1 or v2).
      • default: "v2"
      • tls: determines wether to use TLS.
      • default: false
      • fingerprint: fingerprint to be used if the certificate is self-signed. If the caster’s certificate is known by a publicly-trusted certification authority, fingerprint should be left empty.
      • default: ""
      • rtk_standard: determines the RTK standard, options are auto, RTCMv2, RTCMv3, or CMRv2.
      • default: "auto"
      • send_gga: specifies whether or not to send NMEA GGA messages to the NTRIP caster, and at which rate. It must be one of auto, off, sec1, sec5, sec10 or sec60. In auto mode, the receiver automatically sends GGA messages if requested by the caster.
      • default: "auto"
      • keep_open: determines wether this connection shall be kept open. If set to true the Rx will still be able to receive RTK corrections to improve precision after driver is shut down.
      • default: true
    • ip_server_#: for receiving corretions via TCP/IP (# is from 1 ... 5).
      • id: specifies the IP server IPS1, IPS2, IPS3, IPS4, or IPS5. Note that ROSaic will send GGA messages on this connection if send_gga is set, such that in the Data Link application of RxTools one just needs to set up a TCP client to the host name as found in the ROSaic parameter device with the port as found in port. If the latter connection were connection 1 on Data Link, then connection 2 would set up an NTRIP client connecting to the NTRIP caster as specified in the above parameters in order to forward the corrections from connection 2 to connection 1.
      • default: ""
      • port: its port number of the connection that ROSaic establishes on the receiver. When selecting a port number, make sure to avoid conflicts with other services.
      • default: 0
      • rtk_standard: determines the RTK standard, options are auto, RTCMv2, RTCMv3, or CMRv2.
      • default: ""
      • send_gga: specifies whether or not to send NMEA GGA messages to the NTRIP caster, and at which rate. It must be one of auto, off, sec1, sec5, sec10 or sec60. In auto mode, the receiver sends with sec1.
      • default: "auto"
      • keep_open: determines wether this connection shall be kept open. If set to true the Rx will still be able to receive RTK corrections to improve precision after driver is shut down.
      • default: true
    • serial_#: for receiving corretions via serial connection (# is from 1 ... 5).
      • port: Serial connection COM1, COM2, COM3, USB1, or USB2 on which corrections could be forwarded to the Rx from a serially connected radio link modem or via Data Link for example.
      • default: ""
      • baud_rate: sets the baud rate of this port for genuine serial ports, i.e., not relevant for USB connection.
      • default: 115200
      • rtk_standard: determines the RTK standard, options are auto, RTCMv2, RTCMv3, or CMRv2.
      • default: "auto"
      • send_gga: specifies whether or not to send NMEA GGA messages to the NTRIP caster, and at which rate. It must be one of auto, off, sec1, sec5, sec10 or sec60. In auto mode, the receiver sends with sec1.
      • default: "auto"
      • keep_open: determines wether this connection shall be kept open. If set to true the Rx will still be able to receive RTK corrections to improve precision after driver is shut down.
      • default: true

INS Specs

+ `ins_spatial_config`: Spatial configuration of INS/IMU. Coordinates according to vehicle related frame directions chosen by `use_ros_axis_orientation` (front-left-up if `true` and front-right-down if `false`).
  + `imu_orientation`: IMU sensor orientation
    + Parameters `theta_x`, `theta_y` and `theta_z` are used to determine the sensor orientation with respect to the vehicle frame. Positive angles correspond to a right-handed (clockwise) rotation of the IMU with respect to its nominal orientation (see below). The order of the rotations is as follows: `theta_z` first, then `theta_y`, then `theta_x`.
    + The nominal orientation is where the IMU is upside down and with the `X axis` marked on the receiver pointing to the front of the vehicle. By contrast, for `use_ros_axis_orientation: true`, nominal orientation is where the `Z axis` of the IMU is pointing upwards and also with the `X axis` marked on the receiver pointing to the front of the vehicle.
    + default: `0.0`, `0.0`, `0.0` (degrees)
  + `poi_lever_arm`: The lever arm from the IMU reference point to a user-defined POI
    + Parameters `delta_x`,`delta_y` and `delta_z` refer to the vehicle reference frame
    + default: `0.0`, `0.0`, `0.0` (meters)
  + `ant_lever_arm`: The lever arm from the IMU reference point to the main GNSS antenna
    + The parameters `x`,`y` and `z` refer to the vehicle reference frame
    + default: `0.0`, `0.0`, `0.0` (meters)
  + `vsm_lever_arm`: The lever arm from the IMU reference point to the velocity sensor
    + The parameters `vsm_x`,`vsm_y` and `vsm_z` refer to the vehicle reference frame 
    + default: `0.0`, `0.0`, `0.0` (meters)
+ `ins_initial_heading`: How the receiver obtains the initial INS/GNSS integrated heading during the alignment phase
    + In case it is `auto`, the initial integrated heading is determined from GNSS measurements.
    + In case it is `stored`, the last known heading when the vehicle stopped before switching off the receiver is used as initial heading. Use if vehicle does not move when the receiver is switched off.
    + default: `auto`
+ `ins_std_dev_mask`: Maximum accepted error
  + `att_std_dev`: Configures an output limit on standard deviation of the attitude angles (max error accepted: 5 degrees)
  + `pos_std_dev`: Configures an output limit on standard deviation of the position (max error accepted: 100 meters)
  + default: `5` degrees, `10` meters    
+ `ins_use_poi`: Whether or not to use the POI defined in `ins_spatial_config.poi_lever_arm`
  + If true, the point at which the INS navigation solution (e.g. in `insnavgeod` ROS topic) is calculated will be the POI as defined above (`poi_frame_id`), otherwise it'll be the main GNSS antenna (`frame_id`). Has to be set to `true` if tf shall be published.
  + default: `true`
+ `ins_vsm`: Configuration of the velocity sensor measurements.
  + `ros`: VSM info received from ROS msgs
    + `source`: Specifies which ROS message type shall be used, options are `odometry` or `twist`. Accordingly, a subscriber is established of the type [`nav_msgs/Odometry.msg`](https://docs.ros2.org/foxy/api/nav_msgs/msg/Odometry.html) or [`geometry_msgs/TwistWithCovarianceStamped.msg`](https://docs.ros2.org/foxy/api/geometry_msgs/msg/TwistWithCovarianceStamped.html) listening on the topics `odometry_vsm` or `twist_vsm` respectively. Only linear velocities are evaluated. Measurements have to be with respect to the frame aligned with the vehicle and defined by `ins_spatial_config.vsm_lever_arm` or tf-frame `vsm_frame_id`, see also comment in [`nav_msgs/Odometry.msg`](https://docs.ros2.org/foxy/api/nav_msgs/msg/Odometry.html) that twist should be specified in `child_frame_id`.
      + default: ""
    + `config`: Defines which measurements belonging to the respective axes are forwarded to the INS. In addition, non-holonomic constraints may be introduced for directions known to be restricted in movement. For example, a vehicle with Ackermann steering is limited in its sidewards and upwards movement. So, even if only motion in x-direction may be measured, zero-velocities for y and z may be sent. Only has to be set if `ins_vsm.ros.source`is set to `odometry` or `twist`.
      + default: []
    + `variances_by_parameter`: Wether variances shall be entered by parameter `ins_vsm.ros.variances` or the values from inside the ROS messages are used. Only has to be set if `ins_vsm.source`is set to `odometry` or `twist`.
      + default: false
    + `variances`: Variances of the respective axes. Only have to be set if `ins_vsm.variances_by_parameter` is set to `true`. Values must be > 0.0, else measurements cannot not be used.
      + default: []
  + `ip_server`:
    + `id`: IP server to receive the VSM info (e.g. `IPS2`).
        + default: ""
    + `port`: TCP port to receive the VSM info. When selecting a port number, make sure to avoid conflicts with other services.
      + default: 0
    + `keep_open` determines wether this connections to receive VSM shall be kept open on driver shutdown. If set to `true` the Rx will still be able to use external VSM info to improve its localization.
      + default: `true`
  + `serial`:
    + `port`: Serial port to receive the VSM info.
      + default: ""
    + `baud_rate`: Baud rate of the serial port to receive the VSM info.
      + default: 115200
    + `keep_open` determines wether this connections to receive VSM shall be kept open on driver shutdown. If set to `true` the Rx will still be able to use external VSM info to improve its localization.
      + default: `true`

Logger

+ `activate_debug_log`: `true` if ROS logger level shall be set to debug.

  • Parameters Configuring (Non-)Publishing of ROS Messages

    NMEA/SBF Messages to be Published

    • publish.gpgga: true to publish nmea_msgs/GPGGA.msg messages into the topic /gpgga
    • publish.gprmc: true to publish nmea_msgs/GPRMC.msg messages into the topic /gprmc
    • publish.gpgsa: true to publish nmea_msgs/GPGSA.msg messages into the topic /gpgsa
    • publish.gpgsv: true to publish nmea_msgs/GPGSV.msg messages into the topic /gpgsv
    • publish.measepoch: true to publish septentrio_gnss_driver/MeasEpoch.msg messages into the topic /measepoch
    • publish.galauthstatus: true to publish septentrio_gnss_driver/GALAuthStatus.msg messages into the topic /galauthstatus and corresponding /diganostics
    • publish.aimplusstatus: true to publish septentrio_gnss_driver/RFStatus.msg messages into the topic /rfstatus, septentrio_gnss_driver/AIMPlusStatus.msg messages into /aimplusstatus and corresponding /diganostics. Some information is only available with active OSNMA.
    • publish.pvtcartesian: true to publish septentrio_gnss_driver/PVTCartesian.msg messages into the topic /pvtcartesian
    • publish.pvtgeodetic: true to publish septentrio_gnss_driver/PVTGeodetic.msg messages into the topic /pvtgeodetic
    • publish.basevectorcart: true to publish septentrio_gnss_driver/BaseVectorCart.msg messages into the topic /basevectorcart
    • publish.basevectorgeod: true to publish septentrio_gnss_driver/BaseVectorGeod.msg messages into the topic /basevectorgeod
    • publish.poscovcartesian: true to publish septentrio_gnss_driver/PosCovCartesian.msg messages into the topic /poscovcartesian
    • publish.poscovgeodetic: true to publish septentrio_gnss_driver/PosCovGeodetic.msg messages into the topic /poscovgeodetic
    • publish.velcovcartesian: true to publish septentrio_gnss_driver/VelCovCartesian.msg messages into the topic /velcovcartesian
    • publish.velcovgeodetic: true to publish septentrio_gnss_driver/VelCovGeodetic.msg messages into the topic /velcovgeodetic
    • publish.atteuler: true to publish septentrio_gnss_driver/AttEuler.msg messages into the topic /atteuler
    • publish.attcoveuler: true to publish septentrio_gnss_driver/AttCovEuler.msg messages into the topic /attcoveuler
    • publish.gpst: true to publish sensor_msgs/TimeReference.msg messages into the topic /gpst
    • publish.navsatfix: true to publish sensor_msgs/NavSatFix.msg messages into the topic /navsatfix
    • publish.gpsfix: true to publish gps_msgs/GPSFix.msg messages into the topic /gpsfix
    • publish.pose: true to publish geometry_msgs/PoseWithCovarianceStamped.msg messages into the topic /pose
    • publish.twist: true to publish geometry_msgs/TwistWithCovarianceStamped.msg messages into the topics /twist and /twist_ins respectively
    • publish.diagnostics: true to publish diagnostic_msgs/DiagnosticArray.msg messages into the topic /diagnostics
    • publish.insnavcart: true to publish septentrio_gnss_driver/INSNavCart.msg message into the topic/insnavcart
    • publish.insnavgeod: true to publish septentrio_gnss_driver/INSNavGeod.msg message into the topic/insnavgeod
    • publish.extsensormeas: true to publish septentrio_gnss_driver/ExtSensorMeas.msg message into the topic/extsensormeas
    • publish.imusetup: true to publish septentrio_gnss_driver/IMUSetup.msg message into the topic/imusetup
    • publish.velsensorsetup: true to publish septentrio_gnss_driver/VelSensorSetup.msgs message into the topic/velsensorsetup
    • publish.exteventinsnavcart: true to publish septentrio_gnss_driver/ExtEventINSNavCart.msgs message into the topic/exteventinsnavcart
    • publish.exteventinsnavgeod: true to publish septentrio_gnss_driver/ExtEventINSNavGeod.msgs message into the topic/exteventinsnavgeod
    • publish.imu: true to publish sensor_msgs/Imu.msg message into the topic/imu
    • publish.localization: true to publish nav_msgs/Odometry.msg message into the topic/localization
    • publish.tf: true to broadcast tf of localization. ins_use_poi must also be set to true to publish tf. Note that only one of publish.tf or publish.tf_ecef may be true.
    • publish.localization_ecef: true to publish nav_msgs/Odometry.msg message into the topic/localization related to ECEF frame.
    • publish.tf_ecef: true to broadcast tf of localization related to ECEF frame. ins_use_poi must also be set to true to publish tf. Note that only one of publish.tf or publish.tf_ecef may be true.

ROS Topic Publications

A selection of NMEA sentences, the majority being standardized sentences, and proprietary SBF blocks is translated into ROS messages, partly generic and partly custom, and can be published at the discretion of the user into the following ROS topics. All published ROS messages, even custom ones, start with a ROS generic header std_msgs/Header.msg, which includes the receiver time stamp as well as the frame ID, the latter being specified in the ROS parameter frame_id.

Available ROS Topics

  • /gpgga: publishes nmea_msgs/Gpgga.msg - converted from the NMEA sentence GGA.
  • /gprmc: publishes nmea_msgs/Gprmc.msg - converted from the NMEA sentence RMC.
  • /gpgsa: publishes nmea_msgs/Gpgsa.msg - converted from the NMEA sentence GSA.
  • /gpgsv: publishes nmea_msgs/Gpgsv.msg - converted from the NMEA sentence GSV.
  • /measepoch: publishes custom ROS message septentrio_gnss_driver/MeasEpoch.msg, corresponding to the SBF block MeasEpoch.
  • /galauthstatus: publishes custom ROS message septentrio_gnss_driver/GALAuthStatus.msg, corresponding to the SBF block GALAuthStatus.
  • /rfstatus: publishes custom ROS message septentrio_gnss_driver/RFStatus.msg, compiled from the SBF block RFStatus.
  • /aimplusstatus: publishes custom ROS message septentrio_gnss_driver/AIMPlusStatus.msg, reporting status of AIM+. Converted from SBF blocks RFStatus and optionally GALAuthStatus. For the latter OSNMA has to be activated.
  • /pvtcartesian: publishes custom ROS message septentrio_gnss_driver/PVTCartesian.msg, corresponding to the SBF block PVTCartesian (GNSS case) or INSNavGeod (INS case).
  • /pvtgeodetic: publishes custom ROS message septentrio_gnss_driver/PVTGeodetic.msg, corresponding to the SBF block PVTGeodetic (GNSS case) or INSNavGeod (INS case).
  • /basevectorcart: publishes custom ROS message septentrio_gnss_driver/BaseVectorCart.msg, corresponding to the SBF block BaseVectorCart.
  • /basevectorgeod: publishes custom ROS message septentrio_gnss_driver/BaseVectorGeod.msg, corresponding to the SBF block BaseVectorGeod.
  • /poscovcartesian: publishes custom ROS message septentrio_gnss_driver/PosCovCartesian.msg, corresponding to SBF block PosCovCartesian (GNSS case) or INSNavGeod (INS case).
  • /poscovgeodetic: publishes custom ROS message septentrio_gnss_driver/PosCovGeodetic.msg, corresponding to SBF block PosCovGeodetic (GNSS case) or INSNavGeod (INS case).
  • /velcovcartesian: publishes custom ROS message septentrio_gnss_driver/VelCovCartesian.msg, corresponding to SBF block VelCovCartesian (GNSS case).
  • /velcovgeodetic: publishes custom ROS message septentrio_gnss_driver/VelCovGeodetic.msg, corresponding to SBF block VelCovGeodetic (GNSS case).
  • /atteuler: publishes custom ROS message septentrio_gnss_driver/AttEuler.msg, corresponding to SBF block AttEuler.
  • /attcoveuler: publishes custom ROS message septentrio_gnss_driver/AttCovEuler.msg, corresponding to the SBF block AttCovEuler.
  • /gpst (for GPS Time): publishes generic ROS message sensor_msgs/TimeReference.msg, converted from the PVTGeodetic (GNSS case) or INSNavGeod (INS case) block's GPS time information, stored in its block header.
  • /navsatfix: publishes generic ROS message sensor_msgs/NavSatFix.msg, converted from the SBF blocks PVTGeodetic,PosCovGeodetic (GNSS case) or INSNavGeod (INS case)
  • /gpsfix: publishes generic ROS message gps_msgs/GPSFix.msg, which is much more detailed than sensor_msgs/NavSatFix.msg, converted from the SBF blocks PVTGeodetic, PosCovGeodetic, ChannelStatus, MeasEpoch, AttEuler, AttCovEuler, VelCovGeodetic, DOP (GNSS case) or INSNavGeod, DOP (INS case). In order to publish heading information, the field dip is diverted from its intended meaning an populated with the heading angle and err_dip with its uncertainty.
  • /pose: publishes generic ROS message geometry_msgs/PoseWithCovarianceStamped.msg, converted from the SBF blocks PVTGeodetic, PosCovGeodetic, AttEuler, AttCovEuler (GNSS case) or INSNavGeod (INS case).
    • Note that GNSS provides absolute positioning, while robots are often localized within a local level cartesian frame. The pose field of this ROS message contains position with respect to the absolute ENU frame (longitude, latitude, height), i.e. not a cartesian frame, while the orientation is with respect to a vehicle-fixed (e.g. for mosaic-x5 in moving base mode via the command setAttitudeOffset, ...) !local! NED frame or ENU frame if use_ros_axis_directions is set true. Thus the orientation is !not! given with respect to the same frame as the position is given in. The cross-covariances are hence set to 0.
  • /twist: publishes generic ROS message geometry_msgs/TwistWithCovarianceStamped.msg, converted from the SBF blocks PVTGeodetic and VelCovGeodetic.
  • /twist_ins: publishes generic ROS message geometry_msgs/TwistWithCovarianceStamped.msg, converted from SBF block INSNavGeod.
  • /insnavcart: publishes custom ROS message septentrio_gnss_driver/INSNavCart.msg, corresponding to SBF block INSNavCart
  • /insnavgeod: publishes custom ROS message septentrio_gnss_driver/INSNavGeod.msg, corresponding to SBF block INSNavGeod
  • /extsensormeas: publishes custom ROS message septentrio_gnss_driver/ExtSensorMeas.msg, corresponding to SBF block ExtSensorMeas.
  • /imusetup: publishes custom ROS message septentrio_gnss_driver/IMUSetup.msg, corresponding to SBF block IMUSetup.
  • /velsensorsetup: publishes custom ROS message septentrio_gnss_driver/VelSensorSetup.msg corresponding to SBF block VelSensorSetup.
  • /exteventinsnavcart: publishes custom ROS message septentrio_gnss_driver/INSNavCart.msg, corresponding to SBF block ExtEventINSNavCart.
  • /exteventinsnavgeod: publishes custom ROS message septentrio_gnss_driver/INSNavGeod.msg, corresponding to SBF block ExtEventINSNavGeod.
  • /diagnostics: accepts generic ROS message diagnostic_msgs/DiagnosticArray.msg, converted from the SBF blocks QualityInd, ReceiverStatus and ReceiverSetup
  • /imu: accepts generic ROS message sensor_msgs/Imu.msg, converted from the SBF blocks ExtSensorMeas and INSNavGeod.
    • The ROS message sensor_msgs/Imu.msg can be fed directly into the robot_localization of the ROS navigation stack. Note that use_ros_axis_orientation should be set to true to adhere to the ENU convention.
  • /localization: accepts generic ROS message nav_msgs/Odometry.msg, converted from the SBF block INSNavGeod and transformed to UTM.
    • The ROS message nav_msgs/Odometry.msg can be fed directly into the robot_localization of the ROS navigation stack. Note that use_ros_axis_orientation should be set to true to adhere to the ENU convention.
  • /localization_ecef: accepts generic ROS message nav_msgs/Odometry.msg, converted from the SBF blocks INSNavCart and INSNavGeod.
    • The ROS message nav_msgs/Odometry.msg can be fed directly into the robot_localization of the ROS navigation stack. Note that use_ros_axis_orientation should be set to true to adhere to the ENU convention.

Suggestions for Improvements

Some Ideas + Equip ROSaic with an NTRIP client such that it can forward corrections to the receiver independently of `Data Link`.

Adding New SBF Blocks or NMEA Sentences

Steps to Follow Is there an SBF or NMEA message that is not being addressed while being important to your application? If yes, follow these steps: 1. Find the log reference of interest in the publicly accessible, official documentation. Hence select the reference guide file, e.g. for mosaic-x5 in the [product support section for mosaic-X5](https://www.septentrio.com/en/support/mosaic/mosaic-x5), Chapter 4, of Septentrio's homepage. 2. SBF: Add a new `.msg` file to the `../msg` folder. And modify the `../CMakeLists.txt` file by adding a new entry to the `add_message_files` section. 3. Add msg header and typedef to `typedefs.hpp`. 4. Parsers: - SBF: Add a parser to the `sbf_blocks.hpp` file. - NMEA: Construct two new parsing files such as `gpgga.cpp` to the `../src/septentrio_gnss_driver/parsers/nmea_parsers` folder and one such as `gpgga.hpp` to the `../include/septentrio_gnss_driver/parsers/nmea_parsers` folder. 5. Processing the message/block: - SBF: Extend the `SbfId` enumeration in the `message_handler.hpp` file with a new entry. - SBF: Extend the SBF switch-case in `message_handler.cpp` file with a new case. - NMEA: Extend the `nmeaMap_` in the `message_handler.hpp` file with a new pair. - NMEA: Extend the NMEA switch-case in `message_handler.cpp` file with a new case. 6. Create a new `publish/..` ROSaic parameter in the `../config/rover.yaml` file and create a boolean variable `publish_xxx` in the struct in the `settings.h` file. Parse the parameter in the `rosaic_node.cpp` file. 7. Add SBF block or NMEA to data stream setup in `communication_core.cpp` (function `configureRx()`).
CHANGELOG

Changelog for package septentrio_gnss_driver

1.3.2 (2022-11-19) -----------* Merge pull request #106 from thomasemter/dev/next2 Fix IMU units * Fix topics namespace * Fix units of imu angular rates * Merge pull request #96 from septentrio-gnss/dev2 Dev2 * Contributors: Thomas Emter, Tibor Dome, septentrio-users

1.3.1 (2022-07-06)

  • New Features

    : - Recovery from connection interruption - Add option to bypass configuration of Rx - Add tests - OSNMA - Latency compensation for ROS timestamps - Output of SBf block VelCovCartesian - Support for UDP and TCP via IP server - New VSM handling allows for unknown variances (INS firmware >= 1.4.1) - Add heading angle to GPSFix msg (by diverting dip field, cf. readme)

  • Improvements

    : - Rework IO core and message handling - Unified stream processing - Internal data queue - Prevent message loss in file reading - Add some explanatory warnings for parameter mismatches - Add units to message definitions

  • Fixes

    : - navsatfix for INS - Empty headers - Single antenna receiver setup

  • Preliminary Features

    : - Output of localization and tf in ECEF frame, testing and feedback welcome

  • Commits

    : - Merge pull request #83 from thomasemter/dev/next2 Update readme - Add expected release dates - Add known issues to readme - Update version - Update readme - Merge pull request #82 from thomasemter/dev/next2 Fix spelling - Categorize stream params - Add keep alive check for TCP - Fix spelling - Add TCP communication via static IP server - Add units to msgs - Fix spelling - Merge pull request #76 from thomasemter/dev/next2 upcoming release - Add heading to GPSFix msg - Move constant - Change log level of firmware check - Add improved VSM handling - Change INS in GNSS node detection to auto - Fix invald v_x var case - Refine readme on UDP - Improve server duplicate check - Add more info un UDP configuration - Fix publish check - Add more publishing checks for configured Rx - Add const for max udp packet size - Update readme and changelog - Add device check to node - Fix param name separators - Add checks for IP server duplicates - Add latency compensation to att msgs - Add device check logic - Add UDP params and setup logic - Fix multi msg per packet - Fix localization stamp and tf publishing - Change VSM to be averaged and published with 2 Hz - Change VSM to be averaged and published with 2 Hz - Always publish raw IMU data as indicated - Change to empty fields - Refine diagnostics naming scheme and add trigger to ensure emission of ReceiverSetup - Change diagnostics naming scheme - Add missing new params to gnss.yaml - Expand readme on AIM+ - Reformulate readme about ROS and ROS2 - Add custom message to report AIM+ status - Catch invalid UTM conversion - Robustify command reset - Add RFStatus diagnostics - Add VelCovCartesian output - Refine Rx type check - Add option for latency compensation - Fix param type misinterpretation - Add OSNMA msg and diagnostics - Update changelog - Refine README and fix compiled message logic - Update changelog - Add warning for configuring INS as GNSS - Add warn log for misconfiguration - Fix pose publishing rate - Fix navsatfix publishing - Make vars const - Merge rework of internal IO handling - Change connection thread - Fix attitude cov flipped twice - Add cov alignment from true north to grid north - Rename meridian convergence and fix sense - Remove obsolete define - Add tests - Rename example launch files so they are found by auto-completion - Merge branch \'dev/ros2\' into dev/next2 - Fix lat/long in rad - Fix readme concerning ROS 2 distros - Reorder localization msg filling - Update readme - Fix NED to ECEF rotation matrix - Add localization ECEF publishing - Add ecef localization msg - Add local to ecef transforms - Contributors: Thomas Emter, Tibor Dome

1.2.3 (2022-11-09)

  • New Features

    : - Twist output option - Example config files for GNSS and INS - Get leap seconds from receiver - Firmware check - VSM from odometry or twist ROS messages - Add receiver type in case INS is used in GNSS mode - Add publishing of base vector topics

  • Improvements

    : - Rework RTK corrections parameters and improve flexibility

  • Fixes

    : - /tf not being published without /localization - Twist covariance matrix of localization - Support 5 ms period for IMU explicitly

1.2.2 (2022-06-22)

  • Fixes

    : - Memory corruption under adverse conditions

  • Commits

    : - Merge pull request #66 from thomasemter/dev/next2 Fix memory corruption - Fix parameter warnings - Reset buffer size to 16384 - Update changelog - Fix memory corruption - Replace maps with unordered_maps - Overload timestamp function - Fix frame ids for INS msgs - Add define to avoid usage of deprecated header - Change readme on gps-msgs packet - Add info on user credentials - Fix spelling in readme - Merge remote-tracking branch \'upstream/ros2\' into dev/next2 - Add comment for heading from pose - Contributors: Thomas Emter, Tibor Dome

1.2.1 (2022-05-16)

  • New Features

    : - Add login credentials - Activate NTP server if use_gnss_time is set to true

  • Improvements

    : - Add NED option to localization

  • Fixes

    : - IMU orientation for ROS axis convention

  • Commits

    : - Merge pull request #63 from thomasemter/dev/next2 Small fixes and additions - Merge pull request #60 from wep21/support-rolling fix: modify build error for rolling/humble - Revert change for deprecation warning in Humble - Change links to reflect ROS2 - Amend readme regarding robot_localization - Fix compiler warnings for humble - Add more explanations for IMU orientation in ROS convention - Fix formatting in readme - Fix package name in readme - Update readme - Update changelog - Fix IMU orientation for ROS axis orientation - Activate NTP only if GNSS time is used - Add NED option to localization - Set NMEA header to GP - Update readme and changelog - Activate NTP server - Add credentials for access control - fix: modify build error for rolling/humble - Contributors: Daisuke Nishimatsu, Thomas Emter, Tibor Dome

1.2.0 (2022-04-27)

  • New Features

    : - Add option to use ROS axis orientations according to REP103 - Add frame_id parameters - Add option to get frames from tf - Publishing of cartesian localization in UTM (topic and/or tf) for INS - Publishing of IMU topic for INS - Publishing of MeasEpoch - ROS2 branch

  • Improvements

    : - Add multi antenna option - Increase number of SBF streams - Add option to set polling_period to \"on change\" - Increased buffer size from 8192 to 131072 bytes - Add endianess aware parsers - Only publish topics set to true - Add parameter to switch DEBUG logging on and off - Change GPxxx messages to ROS built-in types - Remove duplicate INS msg types

  • Fixes

    : - Setting of antenna type - Publishing rate interconnections of gpsfix and velcovgeodetic - Missing quotes for antenna type - Broken attitude parsing pose and gpsfix from INS - IMU orientation was not sent to Rx - Graceful shutdown of threads

  • Commits

    : - Merge branch \'dev\' - Prepare new release - Prepare new release - Merge pull request #53 from thomasemter/dev/refactor Very last changes - Add geographic lib dependency to package.xml - Add comment for frame of main antenna - Move utm zone locking section in readme - Reformulate readme section on frames - Merge pull request #52 from thomasemter/dev/refactor Last changes - Change frame id back to poi_frame_id - Make error log more explicit - Merge pull request #49 from thomasemter/dev/refactor Improve IMU blocks sync and do-not-use value handling - Fix buffer size in changelog - Turn off Nagle\'s algorithm for TCP - Fix changelog formatting - Fix readme - Set default base frame to base_link - Fix valid tow check logic - Increase buffer size for extreme stress tests - Fix crc check - Fix and streamline tf handling - Add checks for validity of values - Fix rad vs deg - Update changelog - Add some comments - Set stdDevMask to values > 0.0 in node - Set stdDevMask to values > 0.0 - Add info on RNDIS and set it to default - Increase default serial baud rate - Add parameter to set log level to debug - Change defaults for publishers in node - Put publish params together and fix mismatch in readme - Improve IMU blocks sync and do-not-use value handling - Merge pull request #48 from thomasemter/dev/refactor Fix measepoch not publishing without gpsfix - Fix measepoch not publishing without gpsfix - Merge pull request #47 from thomasemter/dev/refactor Dev/refactor - Publish only messages set to true - Remove leftover declaration - Merge branch \'dev/endianess_agnostic\' into dev/refactor - Update readme to reflect endianess aware parsing - Remove msg smart pointers - Fix array assertion failure - Cleanup - Add ReceiverStatus parser - Add QualityInd parser - Add DOP parser - Add ReceiverSetup parser - Fix MeasEpoch and ChannelStatus parsers, add measepoch publishing - Add ChannelStatus parser - Add MeasEpoch parser - Add IMU and VelSensor setup parsers - Add Cov SBF parsers - Add templated qi parser function - Add AttEuler+Cov parser - Revert ordering change inside INSNav ROS msgs - Add ExtSensorMeas parser - Add PVT parsers - Add range checks to parsers - Replace INSNav grammar with parsers - Test parser vs. grammar for better performance - Fix sb_list check - Add IMU and VelSensor setup grammars - Move adapt ROS header to typedefs.h - Add revision check to MeasEpoch - Fix ReceiverStatus grammar - Extend ReceiverSetup and add revision checks - Change logger and fix loop range - Remove reserved bytes from parsing - Remove obsolete structs - Directly parse Cov SBFs to ROS msg - Directly parse PVT SBFs, remove obsolete ids - Rename rev to revision - Fix block header parsing - Directly parse AttEuler to ROS msg - Directly parse to ROS msgs for INSNavXxx - Exchange pow with square function and remove casts - Merge pull request #46 from thomasemter/dev/refactor Dev/refactor - Simplify sync bytes check - Move tow/wnc to BlockHeader - Adjust order in INSNav ros msgs - Fix INSNav grammars - Change BlockHeader structure - Remove length ref from header - Rectify sb_list check of INSNavXxx - Add automtatic activation of multi-antenna mode - Merge branch \'dev/refactor\' of https://github.com/thomasemter/septentrio_gnss_driver into dev/refactor - Add automtatic activation of multi-antenna mode - Fix wrong scope of phoenix::ref variables - Fix AttEuler grammar - Add max size checks to QualityInd and ReceiverStatus - Replace locals with phoenix::ref in grammars - Add revision dependent parsing to PVTs - Change offset check to epsilon - Change offset check to epsilon - Fix parsing checks - Set has arrived to false on parsing error - Add INSNav grammars - Add abs to offset check - Add abs to offset check - Add Cov grammars - Remove superfluous typdefs of structs - Add ReceiverStatus grammar - Add QualityINd grammar - Merge pull request #45 from thomasemter/dev/refactor Dev/refactor - Add id check to header grammar - Add id check to header grammar - Add ReceiverSetup grammar - Add DOP grammar - Directly intialize vector to parse - Add MeasEpoch grammar - Remove duplicate msg types - Remove obsolete include - Add revision and length return to header grammar - Merge branch \'feature/endianess_agnostic\' into dev/endianess_agnostic - Make multi_antenna option also usable for gnss - Add typedefs plus some minor changes - Add warning concerning pitch angle if antennas are rotated - Add multi antenna option to ins and fix antenna offset decimal places trimming - Fix identation - Distinguish between gnss and ins for spatial config from tf - Merge pull request #43 from thomasemter/dev/refactor Dev/refactor - Add vehicle frame for clarity - Handle missing tf more gently - Merge branch \'dev/spatial_config_via_tf\' into dev/refactor - Update readme - Fix antenna offset from tf - Add automatic publishing of localization if tf is activated - Add automatic publishing of localization if tf is activated - Add spatial config via tf, to be tested - Fix crashes due to parsing errors (replacing uncatched throws) - Add tf broadcasting - Add comments - Add localization in UTM output - Add check to IMU msg sync - Change msg sync to allow for 200 Hz IMU msgs - Add ROS IMU msg - Fix IMU setup message attitude conversion - Fix pose from INS data - Fix IMU raw data rotation compensation - Make antenna attitude offset usable by GNSS - Add ros directions option to pose and fix covariances - Update readme - Merge branch \'feature/ros_axis_orientation\' into dev/refactor - Add nmea_msgs dependencies - Merge branch \'dev/nmea\' into dev/refactor - Update readme - Update readme - Add antenna offsets to conversions - Fix IMU orientation conversion - Change ExtSensorMead temperature to deg C - Add axis orientation info to readme - Fix IMU axis orientation - Change get int param - Update readme to reflect removal of aux antenna offset - Fix different antenna setup message for INS and remove obsolete aux1 antenna offset for GNSS - Fix ExtSensorMeas message filling - Fix ExtSensorMeas message to reflect available fields - Fix missing INS blocks - Fix missing INS blocks - WIP, introduce ros axis orientation option, to be tested - Add option to set pvt rate to OnChange - Add comment on NTP to readme - Change to nmea_msgs - Add automatic addition of needed sub messages - Comment out setting debug level - Add comments and fix spelling errors - Merge pull request #42 from thomasemter/dev/refactor Dev/refactor - Change to quaternion msg typedef - Comment out debug logging - Remove filling of seq field - Change msg definitions to be compatible with ROS2 - Update readme - Change make_shared for portability and add more typedefs - Add get param int fallback for numeric antenna serial numbers - Change Attitude to be published with pvt rate - Add log identifier - Add checks for relevant ros params - Concatenate multiple SBF blocks in streams - Move main into own file - Move get ros time to AsyncManager - Remove obsolete param comment - Move get ros params to base class - Change to nsec timestamp internally - Add publishing functionality to node base class - Move node handle ptr and functions to base class and rename - Add stamp to nmea parsing - Add logging in PcapReader - Add logging in CircularBuffer - Add missed logging - Add logging in AsyncManager - Add getTime function - Add logging in RxMessage - Add logging in CallbackHandlers - Add log function to node by polymorphism, logging in Comm_OI - Fix wait function and force use_gnss_time when reading from file - Add thread shutdown and remove spurious delete - Add typedefs for ins messages - Add typedefs for gnss messages - Add typedefs for ros messages - Refine shutdown - Fix shutdown escalating to SIGTERM - Move waiting for response in send function - Make functions private - Change crc to C++ - Fix variable name - Remove global variables from node cpp file - Move more global settings to settings struct - Move more global settings to settings struct - Move global settings to settings struct - Move more functions to Comm_IO - Move settings to struct and configuration to Comm_IO - Merge branch \'dev/change_utc_calculation\' into dev/refactor - Remove obsolete global variables - Move g_unix_time to class - Make has_arrived booleans class memebers and rx_message a persistent class - Make node handle a class member - Fix parsing of ID and rev - Finish ChannelStatusGrammar, to be tested - WIP, partially fix ChannelStatusGrammar - Add SBF length parsing utility - Insert spirit parsers - WIP, add omission of padding bytes - WIP, add more spirit parsers - Add parsing utilities for tow, wnc and ID - Move getId/Tow/Wnc to parsing utilities - Change UTC calculation to use tow and wnc - WIP, add boost spirit and endian buffers - Change UTC calculation to use tow and wnc

  • ROS2 Commits

    : - Prepare ros2 release - Merge pull request #54 from thomasemter/dev/ros2 ROS2 branch - Port driver to ros2

  • Change UTC calculation to use tow and wnc

  • Contributors: Thomas Emter, Tibor Dome, tibordome

1.0.8 (2021-10-23)

  • Added INS Support

1.0.7 (2021-05-18)

  • Clang formatting, publishing from SBF log, play-back of PCAP files

1.0.6 (2020-10-16)

  • ROSaic binary installation now available on Melodic & Noetic

1.0.5 (2020-10-15)

  • changed repo name
  • v1.0.4
  • 1.0.3
  • Merge pull request #22 from septentrio-gnss/local_tibor New changelog
  • New changelog
  • Merge pull request #21 from septentrio-gnss/local_tibor Added rosdoc.yaml file
  • Merge pull request #20 from septentrio-gnss/local_tibor Improved doxygen annotations
  • Merge pull request #19 from septentrio-gnss/local_tibor Improved doxygen annotations
  • Update README.md
  • Merge pull request #18 from septentrio-gnss/local_tibor Adopted ROS and C++ conventions, added ROS diagnostics msg,
  • Update README.md
  • Update README.md
  • Update README.md
  • Contributors: septentrio-users, tibordome

1.0.4 (2020-10-11)

  • Added rosdoc.yaml file
  • Improved doxygen annotations
  • Improved doxygen annotations
  • Adopted ROS and C++ conventions, added ROS diagnostics msg, removed ROS garbage value bug, added auto-detection of SBF arrival order for composite ROS msgs
  • Merge branch \'master\' of https://github.com/septentrio-gnss/rosaic
  • NTRIP with Datalink, circular buffer, reading connection descriptor, new messages
  • Update README.md
  • Contributors: septentrio-users, tibordome

1.0.3 (2020-09-30)

  • Add new config/rover.yaml file
  • Add config/rover.yaml to .gitignore
  • Merge pull request #17 from septentrio-gnss/local_tibor NTRIP with Datalink, circular buffer, reading connection descriptor..
  • Merge branch \'local_tibor\'
  • NTRIP with Datalink, circular buffer, reading connection descriptor, new messages
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #16 from septentrio-gnss/local_tibor NTRIP parameters added, reconnect_delay_s implemented,
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #15 from tibordome/local_tibor GPSFix completed, datum as new parameter
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #14 from tibordome/local_tibor GPSFix completed, datum as new parameter
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #13 from tibordome/local_tibor Added AttCovEuler.msg and AttEuler.msg
  • Merge pull request #12 from tibordome/local_tibor Fixed service field of NavSatStatus
  • Contributors: Tibor Dome, septentrio-users, tibordome

1.0.2 (2020-09-25)

  • NTRIP parameters added, reconnect_delay_s implemented, package.xml updated, ROSaic now detects connection descriptor automatically, mosaic serial port parameter added
  • GPSFix completed, datum as new parameter, ANT type and marker-to-arp distances as new parameters, BlockLength() method corrected, sending multiple commands to Rx corrected by means of mutex
  • Contributors: tibordome

1.0.1 (2020-09-22)

  • GPSFix completed, datum as new parameter, ANT type and marker-to-arp distances as new parameters, BlockLength() method corrected, sending multiple commands to Rx corrected by means of mutex
  • Added AttCovEuler.msg and AttEuler.msg
  • Fixed service field of NavSatStatus, fixed ROS header\'s seq field of each published ROS message, added write method for sending commands to Rx, successfully tested, added AttEuler, added AttCovEuler
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #11 from tibordome/local_tibor rosconsole_backend_interface dependency not needed
  • rosconsole_backend_interface dependency not needed
  • Merge pull request #10 from tibordome/local_tibor rosconsole_log4cxx dep not needed
  • rosconsole_log4cxx dep not needed
  • Merge pull request #9 from tibordome/local_tibor rosconsole_log4cxx dep not needed
  • rosconsole_log4cxx dep not needed
  • Merge pull request #8 from tibordome/local_tibor Local tibor
  • Update README.md
  • Merge pull request #7 from tibordome/local_tibor Ready for First Release
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #6 from tibordome/local_tibor Local tibor
  • Merge pull request #5 from tibordome/local_tibor TCP seems to work
  • Contributors: Tibor Dome, tibordome

1.0.0 (2020-09-11)

  • Ready for first release
  • Added Gpgga.msg and PosCovGeodetic.msg files
  • Ready for First Release
  • Ready for first release
  • Ready for first release
  • Ready for first release
  • TCP bug removed
  • TCP bug removed
  • TCP seems to work
  • Merge pull request #4 from tibordome/v0.2 V0.2
  • PVTCartesian and PVTGeodetic publishing works on serial
  • PVTCartesian and PVTGeodetic publishing works on serial
  • Merge pull request #3 from tibordome/v0.2 Add doxygen_out and Doxyfile 2nd trial
  • Add doxygen_out and Doxyfile 2nd trial
  • Merge pull request #2 from tibordome/v0.1 Add doxygen_out and Doxyfile
  • Add doxygen_out and Doxyfile
  • Update README.md
  • Create README.md
  • Update LICENSE
  • Merge pull request #1 from tibordome/add-license-1 Create LICENSE
  • Create LICENSE
  • Create LICENSE
  • Commit
  • Successfully tested publishing to /gpgga topic via serial
  • To make sure master branch exists
  • Contributors: Tibor Dome, tibordome

Wiki Tutorials

See ROS Wiki Tutorials for more details.

Source Tutorials

Not currently indexed.

Recent questions tagged septentrio_gnss_driver at Robotics Stack Exchange

septentrio_gnss_driver package from septentrio_gnss_driver repo

septentrio_gnss_driver

Package Summary

Tags No category tags.
Version 1.3.2
License BSD 3-Clause License
Build type CATKIN
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/septentrio-gnss/septentrio_gnss_driver.git
VCS Type git
VCS Version master
Last Updated 2023-11-19
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

ROSaic: C++ driver for Septentrio's mosaic receivers and beyond

Additional Links

Maintainers

  • Septentrio

Authors

  • Tibor Dome

ROSaic = ROS + mosaic

Overview

This repository hosts drivers for ROS (Melodic and Noetic) and ROS 2 (Foxy, Galactic, Humble, Rolling, and beyond) - written in C++ - that work with mosaic and AsteRx - two of Septentrio's cutting-edge GNSS and GNSS/INS receiver families - and beyond. The ROS version is available in this branch, whereas the ROS 2 version is available in the branch ros2.

Main Features: - Supports Septentrio's single antenna GNSS, dual antenna GNSS and INS receivers - Supports serial, TCP/IP and USB connections, the latter being compatible with both serial (RNDIS) and TCP/IP protocols - Supports several ASCII (including key NMEA ones) messages and SBF (Septentrio Binary Format) blocks - Reports status of AIM+ (Advanced Interference Mitigation including OSNMA) anti-jamming and anti-spoofing. - Can publish nav_msgs/Odometry message for INS receivers - Can blend SBF blocks PVTGeodetic, PosCovGeodetic, ChannelStatus, MeasEpoch, AttEuler, AttCovEuler, VelCovGeodetic and DOP in order to publish gps_common/GPSFix and sensor_msgs/NavSatFix messages - Supports axis convention conversion as Septentrio follows the NED convention, whereas ROS is ENU. - Easy configuration of multiple RTK corrections simultaneously (via NTRIP, TCP/IP stream, or serial) - Can play back PCAP capture logs for testing purposes - Tested with the mosaic-X5, mosaic-H, AsteRx-m3 Pro+ and the AsteRx-SBi3 Pro receiver - Easy to add support for more log types

Please let the maintainers know of your success or failure in using the driver with other devices so we can update this page appropriately.

Dependencies

The master branch for this driver functions on both ROS Melodic (Ubuntu 18.04) and Noetic (Ubuntu 20.04). It is thus necessary to install the ROS version that has been designed for your Linux distro.

Additional ROS packages have to be installed for the GPSFix message.

sudo apt install ros-$ROS_DISTRO-nmea-msgs ros-$ROS_DISTRO-gps-common.

The serial and TCP/IP communication interface of the ROS driver is established by means of the Boost C++ library. In the unlikely event that the below installation instructions fail to install Boost on the fly, please install the Boost libraries via

sudo apt install libboost-all-dev.

Compatiblity with PCAP captures are incorporated through pcap libraries. Install the necessary headers via

sudo apt install libpcap-dev.

Conversions from LLA to UTM are incorporated through GeographicLib. Install the necessary headers via

sudo apt install libgeographic-dev

Usage

Binary Install The binary release is now available for Melodic and Noetic. To install the binary package on Melodic for instance, simply run `sudo apt-get install ros-$ROS_DISTRO-septentrio-gnss-driver`.
Build from Source Alternatively, the package can also be built from source using [`catkin_tools`](https://catkin-tools.readthedocs.io/en/latest/installing.html), where the latter can be installed using the command `sudo apt-get install python-catkin-tools` for Melodic or `sudo apt-get install python3-catkin-tools` for Noetic. The typical `catkin_tools` [workflow](https://catkin-tools.readthedocs.io/en/latest/quick_start.html) should suffice: ``` source /opt/ros/${ROS_DISTRO}/setup.bash # In case you do not use the default shell of Ubuntu, you need to source another script, e.g. setup.sh. mkdir -p ~/septentrio/src # Note: Change accordingly dependending on where you want your package to be installed. cd ~/septentrio catkin init # Initialize with a hidden marker file catkin config --cmake-args -DCMAKE_BUILD_TYPE=RelWithDebInfo # CMake build types pass compiler-specific flags to your compiler. This type amounts to a release with debug info, while keeping debugging symbols and doing optimization. I.e. for GCC the flags would be -O2, -g and -DNDEBUG. cd src git clone https://github.com/septentrio-gnss/septentrio_gnss_driver rosdep install . --from-paths -i # Might raise "rosaic: Unsupported OS [mint]" warning, if your OS is Linux Mint, since rosdep does not know Mint (and possible other OSes). In that case, add the "--os=ubuntu:saucy" option to "fool" rosdep into believing it faces some Ubuntu version. The syntax is "--os=OS_NAME:OS_VERSION". catkin build # If catkin cannot find empy, tell catkin to use Python 3 by adding "-DPYTHON_EXECUTABLE=/usr/bin/python3". echo "source ~/septentrio/devel/setup.bash" >> ~/.bashrc # It is convenient if the ROS environment variable is automatically added to your bash session every time a new shell is launched. Again, this works for bash shells only. Also note that if you have more than one ROS distribution installed, ~/.bashrc must only source the setup.bash for the version you are currently using. source ~/.bashrc ```
Notes Before Usage + In your bash sessions, navigating to the ROSaic package can be achieved from anywhere with no more effort than `roscd septentrio_gnss_driver`. + The driver assumes that our anonymous access to the Rx grants us full control rights. This should be the case by default, and can otherwise be changed with the `setDefaultAccessLevel` command. If user control is in place user credentials can be given by parameters `login/user` and `login/password`. + ROSaic only works from C++11 onwards due to std::to_string() etc. + Once the catkin build or binary installation is finished, adapt the `config/rover.yaml` file according to your needs. The `launch/rover.launch` need not be modified. Specify the communication parameters, the ROS messages to be published, the frequency at which the latter should happen etc.:
+ Note for setting `ant_serial_nr` and `ant_aux1_serial_nr`: This is a string parameter, numeric-only serial numbers should be put in quotes. If this is not done a warning will be issued and the driver tries to parse it as integer. + Besides the aforementioned config file `rover.yaml` containing all parameters, specialized launch files for GNSS `config/gnss.yaml` and INS `config/ins.yaml` respectively contain only the relevant parameters in each case. - NOTE: Unless `configure_rx` is set to `false`, this driver will overwrite the previous values of the parameters, even if the value is left to zero in the "yaml" file. + The driver was developed and tested with firmware versions >= 4.10.0 for GNSS and >= 1.3.2 for INS. Receivers with older firmware versions are supported but some features may not be available. Known limitations are: * GNSS with firmware < 4.10.0 does not support IP over USB. * GNSS with firmware < 4.12.1 does not support OSNMA. * INS with firmware < 1.3.2 does not support NTP. * INS with firmware < 1.4 does not support OSNMA. * INS with firmware < 1.4.1 does not support improved VSM handling allowing for unknown variances. * INS with firmware 1.2.0 does not support velocity aiding. * INS with firmware 1.2.0 does not support setting of initial heading. + Known issues: * UDP over USB: Blocks are sent twice on GNSS with firmware <= 4.12.1 and INS with firmware <= 1.4. For GNSS it is fixed in version 4.14 (released on June 15th 2023), for INS it will be fixed in to-be-released 1.4.1 (expected in November 2023). + If `use_ros_axis_orientation` to `true` axis orientations are converted by the driver between NED (Septentrio: yaw = 0 is north, positive clockwise) and ENU (ROS: yaw = 0 is east, positive counterclockwise). There is no conversion when setting this parameter to `false` and the angles will be consistent with the web GUI. :
``` # Example configuration Settings for the Rover Rx device: tcp://192.168.3.1:28784 serial: baudrate: 921600 hw_flow_control: off stream_device: tcp: ip_server: "" port: 0 udp: ip_server: "" port: 0 unicast_ip: "" configure_rx: true login: user: "" password: "" osnma: mode: "off" ntp_server: "" keep_open: true frame_id: gnss imu_frame_id: imu poi_frame_id: base_link vsm_frame_id: vsm aux1_frame_id: aux1 vehicle_frame_id: base_link insert_local_frame: false local_frame_id: odom get_spatial_config_from_tf: true lock_utm_zone: true use_ros_axis_orientation: false receiver_type: gnss datum: Default poi_to_arp: delta_e: 0.0 delta_n: 0.0 delta_u: 0.0 att_offset: heading: 0.0 pitch: 0.0 ant_type: Unknown ant_aux1_type: Unknown ant_serial_nr: Unknown ant_aux1_serial_nr: Unknown leap_seconds: 18 polling_period: pvt: 500 rest: 500 use_gnss_time: false latency_compensation: false rtk_settings: ntrip_1: id: "NTR1" caster: "1.2.3.4" caster_port: 2101 username: "Asterix" password: "password" mountpoint: "mtpt1" version: "v2" tls: true fingerprint: "AA:BB:56:78:90:12: ... 78:90:12:34" rtk_standard: "RTCMv3" send_gga: "auto" keep_open: true ntrip_2: id: "NTR3" caster: "5.6.7.8" caster_port: 2101 username: "Obelix" password: "password" mountpoint: "mtpt2" version: "v2" tls: false fingerprint: "" rtk_standard: "RTCMv2" send_gga: "auto" keep_open: true ip_server_1: id: "IPS3" port: 28785 rtk_standard: "RTCMv2" send_gga: "auto" keep_open: true ip_server_2: id: "IPS5" port: 28786 rtk_standard: "CMRv2" send_gga: "auto" keep_open: true serial_1: port: "COM1" baud_rate: 230400 rtk_standard: "auto" send_gga: "sec1" keep_open: true serial_2: port: "COM2" baud_rate: 230400 rtk_standard: "auto" send_gga: "off" keep_open: true publish: # For both GNSS and INS Rxs navsatfix: false gpsfix: true gpgga: false gprmc: false gpst: false measepoch: false pvtcartesian: false pvtgeodetic: true basevectorcart: false basevectorgeod: false poscovcartesian: false poscovgeodetic: true velcovcartesian: false velcovgeodetic: false atteuler: true attcoveuler: true pose: false twist: false diagnostics: false aimplusstatus: true galauthstatus: false # For GNSS Rx only gpgsa: false gpgsv: false # For INS Rx only insnavcart: false insnavgeod: false extsensormeas: false imusetup: false velsensorsetup: false exteventinsnavcart: false exteventinsnavgeod: false imu: false localization: false tf: false localization_ecef: false tf_ecef: false # INS-Specific Parameters ins_spatial_config: imu_orientation: theta_x: 0.0 theta_y: 0.0 theta_z: 0.0 poi_lever_arm: delta_x: 0.0 delta_y: 0.0 delta_z: 0.0 ant_lever_arm: x: 0.0 y: 0.0 z: 0.0 vsm_lever_arm: vsm_x: 0.0 vsm_y: 0.0 vsm_z: 0.0 ins_initial_heading: auto ins_std_dev_mask: att_std_dev: 5.0 pos_std_dev: 10.0 ins_use_poi: true ins_vsm: source: "twist" config: [true, false, false] variances_by_parameter: true variances: [0.1, 0.0, 0.0] ip_server: id: "IPS2" port: 28787 keep_open: true serial: port: "COM3" baud_rate: 115200 keep_open: true # Logger activate_debug_log: false ``` In order to launch ROSaic, one must specify all `arg` fields of the `rover.launch` file which have no associated default values, i.e. for now only the `param_file_name` field. Hence, the launch command reads `roslaunch septentrio_gnss_driver rover.launch param_file_name:=rover`.

Inertial Navigation System (INS): Basics

  • An Inertial Navigation System (INS) is a device which takes the rotation and acceleration solutions as obtained from its Inertial Measurement Unit (IMU) and combines those with position and velocity information from the GNSS module. Compared to a GNSS system with 7D or 8D (dual-antenna systems) phase space solutions, the combined, Kalman-filtered 9D phase space solution (3 for position, 3 for velocity, 3 for orientation) of an INS is more accurate, more precise and more stable against GNSS outages.
  • The IMU is typically made up of a 3-axis accelerometer, a 3-axis gyroscope and sometimes a 3-axis magnetometer and measures the system's angular rate and acceleration.

    Measure and Compensate for IMU-Antenna Lever Arm

    • The IMU-antenna lever-arm is the relative position between the IMU reference point and the GNSS Antenna Reference Point (ARP), measured in the vehicle frame.
    • In case of AsteRx SBi3, the IMU reference point is clearly marked on the top panel of the receiver. It is important to compensate for the effect of the lever arm, otherwise the receiver may not be able to calculate an accurate INS position.
    • The IMU/antenna position can be changed by specifying the lever arm's x,yand z parameters in the config.yaml file under the ins_spatial_config/ant_lever_arm parameter.

    Screenshot from 2021-08-03 09-23-19 (1)

    Compensate for IMU Orientation + It is important to take into consideration the mounting direction of the IMU in the body frame of the vehicle. For e.g. when the receiver is installed horizontally with the front panel facing the direction of travel, we must compensate for the IMU’s orientation to make sure the IMU reference frame is aligned with the vehicle reference frame. The IMU position and orientation is printed on the top panel, cf. image below. + The IMU's orientation can be changed by specifying the orientation angles theta_x,theta_yand theta_z in the config.yaml file under the ins_spatial_config/imu_orientation + The below image illustrates the orientation of the IMU reference frame with the associated IMU orientation for the depicted installation. Note that for use_ros_axis_orientation: true sensor_default is the top left position.

    Capture (1)

  • These Steps should be followed to configure the receiver in INS integration mode:

    • Specify receiver_type: ins
    • Specify the orientation of the IMU sensor with respect to your vehicle, using the ins_spatial_config/imu_orientation parameter.
    • Specify the IMU-antenna lever arm in the vehicle reference frame. This is the vector starting from the IMU reference point to the ARP of the main GNSS antenna. This can be done by means of the ins_spatial_config/ant_lever_arm parameter. Specify ins_spatial_config/vsm_lever_arm if measurements of a velocity sensor is available.
    • Alternatively the lever arms may be specified via tf. Set get_spatial_config_from_tfto true in this case.
    • If the point of interest is neither the IMU nor the ARP of the main GNSS antenna, the vector between the IMU and the point of interest can be provided with the ins_solution/poi_lever_arm parameter.
  • For further more information about Septentrio receivers, visit Septentrio support resources or check out the user manual and reference guide of the AsteRx SBi3 receiver.

ROSaic Parameters

The following is a list of ROSaic parameters found in the config/rover.yaml file. * Parameters Configuring Communication Ports and Processing of GNSS and INS Data

Connectivity Specs

  • device: location of main device connection. This interface will be used for setup communication and VSM data for INS. Incoming data streams of SBF blocks and NMEA sentences are recevied either via this interface or a static IP server for TCP and/or UDP. The former will be utilized if section stream_device/tcp and stream_device/udp are not configured.
    • serial:xxx format for serial connections, where xxx is the device node, e.g. serial:/dev/ttyS0. If using serial over USB, it is recommended to specify the port by ID as the Rx may get a different ttyXXX on reconnection, e.g. serial:/dev/serial/by-id/usb-Septentrio_Septentrio_USB_Device_xyz.
    • file_name:path/to/file.sbf format for publishing from an SBF log
    • file_name:path/to/file.pcap format for publishing from PCAP capture.
      • Regarding the file path, ROS_HOME=`pwd` in front of roslaunch septentrio... might be useful to specify that the node should be started using the executable's directory as its working-directory.
    • tcp://host:port format for TCP/IP connections
      • 28784 should be used as the default (command) port for TCP/IP connections. If another port is specified, the receiver needs to be (re-)configured via the Web Interface before ROSaic can be used.
      • An RNDIS IP interface is provided via USB, assigning the address 192.168.3.1 to the receiver. This should work on most modern Linux distributions. To verify successful connection, open a web browser to access the web interface of the receiver using the IP address 192.168.3.1.
    • default: tcp://192.168.3.1:28784
  • serial: specifications for serial communication
    • baudrate: serial baud rate to be used in a serial connection. Ensure the provided rate is sufficient for the chosen SBF blocks. For example, activating MeasEpoch (also necessary for /gpsfix) may require up to almost 400 kBit/s.
    • hw_flow_control: specifies whether the serial (the Rx's COM ports, not USB1 or USB2) connection to the Rx should have UART hardware flow control enabled or not
      • off to disable UART hardware flow control, RTS|CTS to enable it
    • default: 921600, USB1, off
  • stream_device: If left unconfigured, by default device is utilized for the data streams. Within stream_device static IP servers may be defined instead. In config mode (configure_rx set to true), TCP will be prioritized over UDP. If Rx is pre-configured, both may be set simultaneously.
    • tcp: specifications for static TCP server of SBF blocks and NMEA sentences.
      • ip_server: IP server of Rx to be used, e.g. “IPS1”.
      • port: UDP destination port.
    • udp: specifications for low latency UDP reception of SBF blocks and NMEA sentences.
      • ip_server: IP server of Rx to be used, e.g. “IPS1”.
      • port: UDP destination port.
      • unicast_ip: Set to computer's IP to use unicast (optional). If not set multicast will be used.
  • login: credentials for user authentication to perform actions not allowed to anonymous users. Leave empty for anonymous access.
    • user: user name
    • password: password

OSNMA

  • osnma: Configuration of the Open Service Navigation Message Authentication (OSNMA) feature.
    • mode: Three operating modes are supported: off where OSNMA authentication is disabled, loose where satellites are included in the PVT if they are successfully authenticated or if their authentication status is unknown, and strict where only successfully-authenticated satellites are included in the PVT. In case of strict synchronization via NTP is mandatory.
      • default: off
    • ntp_server: In strict mode, OSNMA authentication requires the availability of external time information. In loose mode, this is optional but recommended for enhanced security. The receiver can connect to an NTP time server for this purpose. Options are default to let the receiver choose an NTP server or specify one like pool.ntp.org for example.
      • default: ""
    • keep_open: Wether OSNMA shall be kept active on driver shutdown.
      • default: true

Receiver Configuration

+ configure_rx: Wether to configure the Rx according to the config file. If set to `false`, the Rx has to be configured via the web interface and the settings must be saved. On the driver side communication has to set accordingly to serial, TCP or UDP (TCP and UDP may even be used simultaneously in this case). For TCP communication it is recommended to use a static TCP server (`stream_device/tcp/ip_server` and `stream_device/tcp/port`), since dynamic connections (`device` is tcp) are not guaranteed to have the same id on reconnection. It should also be ensured that obligatory SBF blocks are activated (as of now: ReceiverTime if `use_gnss_time` is set to `true`; `PVTGeodetic`or `PVTCartesian` if latency compensation for PVT related blocks shall be used). Further, if ROS messages compiled from multiple SBF blocks, it should be ensured that all necessary blocks are activated with matching periods, details can be found in section [ROS Topic Publications](#ros-topic-publications). The messages that shall be published still have to be set to `true` in the *NMEA/SBF Messages to be Published* section. Also, parameters concerning the connection and node setup are still relevant (sections: *Connectivity Specs*, *receiver type*, *Frame IDs*, *UTM Zone Locking*, *Time Systems*, *Logger*).
  + default: true

Receiver Type

  • receiver_type: This parameter is to select the type of the Septentrio receiver
    • gnss for GNSS receivers.
    • ins for INS receivers.
    • default: gnss
  • multi_antenna: Whether or not the Rx has multiple antennas.
    • default: false

Frame IDs

  • frame_id: name of the ROS tf frame for the Rx, placed in the header of published GNSS messages. It corresponds to the frame of the main antenna.
    • In ROS, the tf package lets you keep track of multiple coordinate frames over time. The frame ID will be resolved by tf_prefix if defined. If a ROS message has a header (all of those we publish do), the frame ID can be found via rostopic echo /topic, where /topic is the topic into which the message is being published.
    • default: gnss
  • imu_frame_id: name of the ROS tf frame for the IMU, placed in the header of published IMU message
    • default: imu
  • poi_frame_id: name of the ROS tf frame for the POI, placed in the child frame_id of localization if ins_use_poi is set to true.
    • default: base_link
  • vsm_frame_id: name of the ROS tf frame for the velocity sensor.
    • default: vsm
  • aux1_frame_id: name of the ROS tf frame for the aux1 antenna.
    • default: aux1
  • vehicle_frame_id: name of the ROS tf frame for the vehicle. Default is the same as poi_frame_id but may be set otherwise.
    • default: base_link
  • local_frame_id: name of the ROS tf frame for the local frame.
    • default: odom
  • insert_local_frame: Wether to insert a local frame to published tf according to ROS REP 105. The transform from the local frame specified by local_frame_id to the vehicle frame specified by vehicle_frame_id has to be provided, e.g. by odometry. Insertion of the local frame means the transform between local frame and global frame is published instead of transform between vehicle frame and global frame.
    • default: false
  • get_spatial_config_from_tf: wether to get the spatial config via tf with the above mentioned frame ids. This will override spatial settings of the config file. For receiver type ins with multi_antenna set to true all frames have to be provided, with multi_antenna set to false, aux1_frame_id is not necessary. For type gnss with dual-antenna setup only frame_id, aux1_frame_id, and poi_frame_id are needed. For single-antenna gnss no frames are needed. Keep in mind that tf has a tree structure. Thus, poi_frame_id is the base for all mentioned frames.
    • default: false
  • use_ros_axis_orientation Wether to use ROS axis orientations according to ROS REP 103 for body related frames and geographic frames. Body frame directions affect INS lever arms and IMU orientation setup parameters. Geographic frame directions affect orientation Euler angles for INS+GNSS and attitude of dual-antenna GNSS. If use_ros_axis_orientation is set to true, the driver converts between the NED convention (Septentrio: yaw = 0 is north, positive clockwise), and ENU convention (ROS: yaw = 0 is east, positive counterclockwise). There is no conversion when setting this parameter to false and the angles will be consistent with the web GUI in this case.
    • If set to false Septentrios definition is used, i.e., front-right-down body related frames and NED (north-east-down) for orientation frames.
    • If set to true ROS definition is used, i.e., front-left-up body related frames and ENU (east-north-up) for orientation frames.
    • default: true

UTM Zone Locking

  • lock_utm_zone: wether the UTM zone of the initial localization is locked, i.e., this zone is kept even if a zone transition would occur.
    • default: true

Datum

  • datum: With this command, the datum the coordinates should refer to is selected. With setting it to Default, the datum depends on the positioning mode, e.g. WGS84 for standalone positioning.
    • Since the standardized GGA message does only provide the orthometric height (= MSL height = distance from Earth's surface to geoid) and the geoid undulation (distance from geoid to ellipsoid) for which non-WGS84 datums cannot be specified, it does not affect the GGA message.
    • default: Default

POI-ARP Offset

  • poi_to_arp: offsets of the main GNSS antenna reference point (ARP) with respect to the point of interest (POI = marker). Use for static receivers only.
    • The parameters delta_e, delta_n and delta_u are the offsets in the East, North and Up (ENU) directions respectively, expressed in meters.
    • All absolute positions reported by the receiver are POI positions, obtained by subtracting this offset from the ARP. The purpose is to take into account the fact that the antenna may not be located directly on the surveying POI.
    • default: 0.0, 0.0 and 0.0

Antenna Attitude Offset

+ `att_offset`: Angular offset between two antennas (Main and Aux) and vehicle frame
+ `heading`: The perpendicular (azimuth) axis can be compensated for by adjusting the `heading` parameter
+ `pitch`: Vertical (elevation) offset can be compensated for by adjusting the `pitch` parameter
+ default: `0.0`, `0.0` (degrees)

Antenna Specs

  • ant_type: type of your main GNSS antenna
    • For best positional accuracy, it is recommended to select a type from the list returned by the command lstAntennaInfo, Overview. This is the list of antennas for which the receiver can compensate for phase center variation.
    • By default and if ant_type does not match any entry in the list returned by lstAntennaInfo, Overview, the receiver will assume that the phase center variation is zero at all elevations and frequency bands, and the position will not be as accurate.
    • default: Unknown
  • ant_serial_nr: serial number of your main GNSS antenna
  • ant_aux1_type and ant_aux1_serial_nr: same for Aux1 antenna

Leap Seconds

  • leap_seconds: Leap seconds are automatically gathered from the receiver via the SBF block ReceiverTime. If a log file is used for simulation and this block was not recorded, the number of leap seconds that have been inserted up until the point of ROSaic usage can be set by this parameter.
    • At the time of writing the code (2020), the GPS time, which is unaffected by leap seconds, was ahead of UTC time by 18 leap seconds. Adapt the leap_seconds parameter accordingly as soon as the next leap second is inserted into the UTC time or in case you are using ROSaic for the purpose of simulations.

Polling Periods

  • polling_period/pvt: desired period in milliseconds between the polling of two consecutive PVTGeodetic, PosCovGeodetic, PVTCartesian and PosCovCartesian blocks and - if published - between the publishing of two of the corresponding ROS messages (e.g. septentrio_gnss_driver/PVTGeodetic.msg). Consult firmware manual for allowed periods. If the period is set to a lower value than the receiver is capable of, it will be published with the next higher period. If set to 0, the SBF blocks are output at their natural renewal rate (OnChange).
  • polling_period/rest: desired period in milliseconds between the polling of all other SBF blocks and NMEA sentences not addressed by the previous parameter, and - if published - between the publishing of all other ROS messages
    • default: 500 (2 Hz)

Time Systems

  • use_gnss_time: true if the ROS message headers' unix epoch time field shall be constructed from the TOW/WNC (in the SBF case) and UTC (in the NMEA case) data, false if those times shall be taken by the driver from ROS time. If use_gnss_time is set to true, make sure the ROS system is synchronized to an NTP time server either via internet or ideally via the Septentrio receiver since the latter serves as a Stratum 1 time server not dependent on an internet connection. The NTP server of the receiver is automatically activated on the Septentrio receiver (for INS/GNSS a firmware >= 1.3.3 is needed).
    • default: true
  • latency_compensation: Rx reports processing latency in PVT and INS blocks. If set to truethis latency is subtracted from ROS timestamps in related blocks (i.e., use_gnss_time set to false). Related blocks are INS, PVT, Covariances, and BaseVectors. In case of use_gnss_time set to true, the latency is already compensated within the RX and included in the reported timestamps.
    • default: false

RTK corrections

  • rtk_settings: determines RTK connection parameters
    • There are multiple possibilities to feed RTK corrections to the Rx. They may be set simultaneously and the Rx will choose the nearest source.
      • a) ntrip_# if the Rx has internet access and is able to receieve NTRIP streams from a caster. Up to three NTRIP connections are possible.
      • b) ip_server_# if corrections are to be receieved via TCP/IP for example over Data Link from Septentrio's RxTools is installed on a computer. Up to five IP server connections are possible.
      • c) serial_# if corrections are to be receieved via a serial port for example over radio link from a local RTK base or over Data Link from Septentrio's RxTools installed on a computer. Up to five serial connections are possible.
    • ntrip_#: for receiving corretions from an NTRIP caster (# is from 1 ... 3).
      • id: NTRIP connection NTR1, NTR2, or NTR3.
      • default: ""
      • caster: is the hostname or IP address of the NTRIP caster to connect to.
      • default: ""
      • caster_port: IP port of the NTRIP caster.
      • default: 2021
      • username: user name for the NTRIP caster.
      • default: ""
      • pasword: password for the NTRIP caster. The receiver encrypts the password so that it cannot be read back with the command "getNtripSettings".
      • default: ""
      • mountpoint: mount point of the NTRP caster to be used.
      • default: ""
      • version: argument specifies which version of the NTRIP protocol to use (v1 or v2).
      • default: "v2"
      • tls: determines wether to use TLS.
      • default: false
      • fingerprint: fingerprint to be used if the certificate is self-signed. If the caster’s certificate is known by a publicly-trusted certification authority, fingerprint should be left empty.
      • default: ""
      • rtk_standard: determines the RTK standard, options are auto, RTCMv2, RTCMv3, or CMRv2.
      • default: "auto"
      • send_gga: specifies whether or not to send NMEA GGA messages to the NTRIP caster, and at which rate. It must be one of auto, off, sec1, sec5, sec10 or sec60. In auto mode, the receiver automatically sends GGA messages if requested by the caster.
      • default: "auto"
      • keep_open: determines wether this connection shall be kept open. If set to true the Rx will still be able to receive RTK corrections to improve precision after driver is shut down.
      • default: true
    • ip_server_#: for receiving corretions via TCP/IP (# is from 1 ... 5).
      • id: specifies the IP server IPS1, IPS2, IPS3, IPS4, or IPS5. Note that ROSaic will send GGA messages on this connection if send_gga is set, such that in the Data Link application of RxTools one just needs to set up a TCP client to the host name as found in the ROSaic parameter device with the port as found in port. If the latter connection were connection 1 on Data Link, then connection 2 would set up an NTRIP client connecting to the NTRIP caster as specified in the above parameters in order to forward the corrections from connection 2 to connection 1.
      • default: ""
      • port: its port number of the connection that ROSaic establishes on the receiver. When selecting a port number, make sure to avoid conflicts with other services.
      • default: 0
      • rtk_standard: determines the RTK standard, options are auto, RTCMv2, RTCMv3, or CMRv2.
      • default: ""
      • send_gga: specifies whether or not to send NMEA GGA messages to the NTRIP caster, and at which rate. It must be one of auto, off, sec1, sec5, sec10 or sec60. In auto mode, the receiver sends with sec1.
      • default: "auto"
      • keep_open: determines wether this connection shall be kept open. If set to true the Rx will still be able to receive RTK corrections to improve precision after driver is shut down.
      • default: true
    • serial_#: for receiving corretions via serial connection (# is from 1 ... 5).
      • port: Serial connection COM1, COM2, COM3, USB1, or USB2 on which corrections could be forwarded to the Rx from a serially connected radio link modem or via Data Link for example.
      • default: ""
      • baud_rate: sets the baud rate of this port for genuine serial ports, i.e., not relevant for USB connection.
      • default: 115200
      • rtk_standard: determines the RTK standard, options are auto, RTCMv2, RTCMv3, or CMRv2.
      • default: "auto"
      • send_gga: specifies whether or not to send NMEA GGA messages to the NTRIP caster, and at which rate. It must be one of auto, off, sec1, sec5, sec10 or sec60. In auto mode, the receiver sends with sec1.
      • default: "auto"
      • keep_open: determines wether this connection shall be kept open. If set to true the Rx will still be able to receive RTK corrections to improve precision after driver is shut down.
      • default: true

INS Specs

+ `ins_spatial_config`: Spatial configuration of INS/IMU. Coordinates according to vehicle related frame directions chosen by `use_ros_axis_orientation` (front-left-up if `true` and front-right-down if `false`).
  + `imu_orientation`: IMU sensor orientation
    + Parameters `theta_x`, `theta_y` and `theta_z` are used to determine the sensor orientation with respect to the vehicle frame. Positive angles correspond to a right-handed (clockwise) rotation of the IMU with respect to its nominal orientation (see below). The order of the rotations is as follows: `theta_z` first, then `theta_y`, then `theta_x`.
    + The nominal orientation is where the IMU is upside down and with the `X axis` marked on the receiver pointing to the front of the vehicle. By contrast, for `use_ros_axis_orientation: true`, nominal orientation is where the `Z axis` of the IMU is pointing upwards and also with the `X axis` marked on the receiver pointing to the front of the vehicle.
    + default: `0.0`, `0.0`, `0.0` (degrees)
  + `poi_lever_arm`: The lever arm from the IMU reference point to a user-defined POI
    + Parameters `delta_x`,`delta_y` and `delta_z` refer to the vehicle reference frame
    + default: `0.0`, `0.0`, `0.0` (meters)
  + `ant_lever_arm`: The lever arm from the IMU reference point to the main GNSS antenna
    + The parameters `x`,`y` and `z` refer to the vehicle reference frame
    + default: `0.0`, `0.0`, `0.0` (meters)
  + `vsm_lever_arm`: The lever arm from the IMU reference point to the velocity sensor
    + The parameters `vsm_x`,`vsm_y` and `vsm_z` refer to the vehicle reference frame 
    + default: `0.0`, `0.0`, `0.0` (meters)
+ `ins_initial_heading`: How the receiver obtains the initial INS/GNSS integrated heading during the alignment phase
    + In case it is `auto`, the initial integrated heading is determined from GNSS measurements.
    + In case it is `stored`, the last known heading when the vehicle stopped before switching off the receiver is used as initial heading. Use if vehicle does not move when the receiver is switched off.
    + default: `auto`
+ `ins_std_dev_mask`: Maximum accepted error
  + `att_std_dev`: Configures an output limit on standard deviation of the attitude angles (max error accepted: 5 degrees)
  + `pos_std_dev`: Configures an output limit on standard deviation of the position (max error accepted: 100 meters)
  + default: `5` degrees, `10` meters    
+ `ins_use_poi`: Whether or not to use the POI defined in `ins_spatial_config/poi_lever_arm`
  + If true, the point at which the INS navigation solution (e.g. in `insnavgeod` ROS topic) is calculated will be the POI as defined above (`poi_frame_id`), otherwise it'll be the main GNSS antenna (`frame_id`). Has to be set to `true` if tf shall be published.
  + default: `true`
+ `ins_vsm`: Configuration of the velocity sensor measurements.
  + `ros`: VSM info received from ROS msgs
    + `source`: Specifies which ROS message type shall be used, options are `odometry`or `twist`. Accordingly, a subscriber is established of the type [`nav_msgs/Odometry.msg`](https://docs.ros.org/en/api/nav_msgs/html/msg/Odometry.html) or [`geometry_msgs/TwistWithCovarianceStamped.msg`](https://docs.ros.org/en/api/sensor_msgs/html/msg/TwistWithCovarianceStamped.html) listening on the topics `odometry_vsm` or `twist_vsm` respectively. Only linear velocities are evaluated. Measurements have to be with respect to the frame aligned with the vehicle and defined by `ins_spatial_config.vsm_lever_arm` or tf-frame `vsm_frame_id`, see also comment in [`nav_msgs/Odometry.msg`](https://docs.ros.org/en/api/nav_msgs/html/msg/Odometry.html) that twist should be specified in `child_frame_id`.
      + default: ""
    + `config`: Defines which measurements belonging to the respective axes are forwarded to the INS. In addition, non-holonomic constraints may be introduced for directions known to be restricted in movement. For example, a vehicle with Ackermann steering is limited in its sidewards and upwards movement. So, even if only motion in x-direction may be measured, zero-velocities for y and z may be sent.
      + default: []
    + `variances_by_parameter`: Wether variances shall be entered by parameter `ins_vsm/ros/variances` or the values from inside the ROS messages are used.
      + default: false
    + `variances`: Variances of the respective axes. Only have to be set if `ins_vsm/ros/variances_by_parameter` is set to `true`. Values must be > 0.0, else measurements cannot not be used. 
      + default: []
  + `ip_server`:
    + `id`: IP server to receive the VSM info (e.g. `IPS2`).
        + default: ""
    + `port`: TCP port to receive the VSM info. When selecting a port number, make sure to avoid conflicts with other services.
      + default: 0
    + `keep_open` determines wether this connections to receive VSM shall be kept open on driver shutdown. If set to `true` the Rx will still be able to use external VSM info to improve its localization.
      + default: `true`
  + `serial`:
    + `port`: Serial port to receive the VSM info.
      + default: ""
    + `baud_rate`: Baud rate of the serial port to receive the VSM info.
      + default: 115200
    + `keep_open` determines wether this connections to receive VSM shall be kept open on driver shutdown. If set to `true` the Rx will still be able to use external VSM info to improve its localization.
      + default: `true`

Logger

+ `activate_debug_log`: `true` if ROS logger level shall be set to debug.

  • Parameters Configuring Publishing of ROS Messages

    NMEA/SBF Messages to be Published

    • publish/gpgga: true to publish nmea_msgs/GPGGA.msg messages into the topic /gpgga
    • publish/gprmc: true to publish nmea_msgs/GPRMC.msg messages into the topic /gprmc
    • publish/gpgsa: true to publish nmea_msgs/GPGSA.msg messages into the topic /gpgsa
    • publish/gpgsv: true to publish nmea_msgs/GPGSV.msg messages into the topic /gpgsv
    • publish/measepoch: true to publish septentrio_gnss_driver/MeasEpoch.msg messages into the topic /measepoch
    • publish/galauthstatus: true to publish septentrio_gnss_driver/GALAuthStatus.msg messages into the topic /galauthstatus and corresponding /diganostics
    • publish/aimplusstatus: true to publish septentrio_gnss_driver/RFStatus.msg messages into the topic /rfstatus, septentrio_gnss_driver/AIMPlusStatus.msg messages into /aimplusstatus and corresponding /diganostics. Some information is only available with active OSNMA.
    • publish/pvtcartesian: true to publish septentrio_gnss_driver/PVTCartesian.msg messages into the topic /pvtcartesian
    • publish/pvtgeodetic: true to publish septentrio_gnss_driver/PVTGeodetic.msg messages into the topic /pvtgeodetic
    • publish/basevectorcart: true to publish septentrio_gnss_driver/BaseVectorCart.msg messages into the topic /basevectorcart
    • publish/basevectorgeod: true to publish septentrio_gnss_driver/BaseVectorGeod.msg messages into the topic /basevectorgeod
    • publish/poscovcartesian: true to publish septentrio_gnss_driver/PosCovCartesian.msg messages into the topic /poscovcartesian
    • publish/poscovgeodetic: true to publish septentrio_gnss_driver/PosCovGeodetic.msg messages into the topic /poscovgeodetic
    • publish/velcovcartesian: true to publish septentrio_gnss_driver/VelCovCartesian.msg messages into the topic /velcovcartesian
    • publish/velcovgeodetic: true to publish septentrio_gnss_driver/VelCovGeodetic.msg messages into the topic /velcovgeodetic
    • publish/atteuler: true to publish septentrio_gnss_driver/AttEuler.msg messages into the topic /atteuler
    • publish/attcoveuler: true to publish septentrio_gnss_driver/AttCovEuler.msg messages into the topic /attcoveuler
    • publish/gpst: true to publish sensor_msgs/TimeReference.msg messages into the topic /gpst
    • publish/navsatfix: true to publish sensor_msgs/NavSatFix.msg messages into the topic /navsatfix
    • publish/gpsfix: true to publish gps_common/GPSFix.msg messages into the topic /gpsfix
    • publish/pose: true to publish geometry_msgs/PoseWithCovarianceStamped.msg messages into the topic /pose
    • publish/twist: true to publish geometry_msgs/TwistWithCovarianceStamped.msg messages into the topics /twist and /twist_ins respectively
    • publish/diagnostics: true to publish diagnostic_msgs/DiagnosticArray.msg messages into the topic /diagnostics
    • publish/insnavcart: true to publish septentrio_gnss_driver/INSNavCart.msg message into the topic/insnavcart
    • publish/insnavgeod: true to publish septentrio_gnss_driver/INSNavGeod.msg message into the topic/insnavgeod
    • publish/extsensormeas: true to publish septentrio_gnss_driver/ExtSensorMeas.msg message into the topic/extsensormeas
    • publish/imusetup: true to publish septentrio_gnss_driver/IMUSetup.msg message into the topic/imusetup
    • publish/velsensorsetup: true to publish septentrio_gnss_driver/VelSensorSetup.msgs message into the topic/velsensorsetup
    • publish/exteventinsnavcart: true to publish septentrio_gnss_driver/ExtEventINSNavCart.msgs message into the topic/exteventinsnavcart
    • publish/exteventinsnavgeod: true to publish septentrio_gnss_driver/ExtEventINSNavGeod.msgs message into the topic/exteventinsnavgeod
    • publish/imu: true to publish sensor_msgs/Imu.msg message into the topic/imu
    • publish/localization: true to publish nav_msgs/Odometry.msg message into the topic/localization
    • publish/tf: true to broadcast tf of localization. ins_use_poi must also be set to true to publish tf. Note that only one of publish/tf or publish/tf_ecef may be true.
    • publish/localization_ecef: true to publish nav_msgs/Odometry.msg message into the topic/localization related to ECEF frame.
    • publish/tf_ecef: true to broadcast tf of localization related to ECEF frame. ins_use_poi must also be set to true to publish tf. Note that only one of publish/tf or publish/tf_ecef may be true.

ROS Topic Publications

A selection of NMEA sentences, the majority being standardized sentences, and proprietary SBF blocks is translated into ROS messages, partly generic and partly custom, and can be published at the discretion of the user into the following ROS topics. All published ROS messages, even custom ones, start with a ROS generic header std_msgs/Header.msg, which includes the receiver time stamp as well as the frame ID, the latter being specified in the ROS parameter frame_id.

Available ROS Topics

  • /gpgga: publishes nmea_msgs/Gpgga.msg - converted from the NMEA sentence GGA.
  • /gprmc: publishes nmea_msgs/Gprmc.msg - converted from the NMEA sentence RMC.
  • /gpgsa: publishes nmea_msgs/Gpgsa.msg - converted from the NMEA sentence GSA.
  • /gpgsv: publishes nmea_msgs/Gpgsv.msg - converted from the NMEA sentence GSV.
  • /measepoch: publishes custom ROS message septentrio_gnss_driver/MeasEpoch.msg, corresponding to the SBF block MeasEpoch.
  • /galauthstatus: publishes custom ROS message septentrio_gnss_driver/GALAuthStatus.msg, corresponding to the SBF block GALAuthStatus.
  • /rfstatus: publishes custom ROS message septentrio_gnss_driver/RFStatus.msg, compiled from the SBF block RFStatus.
  • /aimplusstatus: publishes custom ROS message septentrio_gnss_driver/AIMPlusStatus.msg, reporting status of AIM+. Converted from SBF blocks RFStatus and optionally GALAuthStatus. For the latter OSNMA has to be activated.
  • /pvtcartesian: publishes custom ROS message septentrio_gnss_driver/PVTCartesian.msg, corresponding to the SBF block PVTCartesian (GNSS case) or INSNavGeod (INS case).
  • /pvtgeodetic: publishes custom ROS message septentrio_gnss_driver/PVTGeodetic.msg, corresponding to the SBF block PVTGeodetic (GNSS case) or INSNavGeod (INS case).
  • /basevectorcart: publishes custom ROS message septentrio_gnss_driver/BaseVectorCart.msg, corresponding to the SBF block BaseVectorCart.
  • /basevectorgeod: publishes custom ROS message septentrio_gnss_driver/BaseVectorGeod.msg, corresponding to the SBF block BaseVectorGeod.
  • /poscovcartesian: publishes custom ROS message septentrio_gnss_driver/PosCovCartesian.msg, corresponding to SBF block PosCovCartesian (GNSS case) or INSNavGeod (INS case).
  • /poscovgeodetic: publishes custom ROS message septentrio_gnss_driver/PosCovGeodetic.msg, corresponding to SBF block PosCovGeodetic (GNSS case) or INSNavGeod (INS case).
  • /velcovcartesian: publishes custom ROS message septentrio_gnss_driver/VelCovCartesian.msg, corresponding to SBF block VelCovCartesian (GNSS case).
  • /velcovgeodetic: publishes custom ROS message septentrio_gnss_driver/VelCovGeodetic.msg, corresponding to SBF block VelCovGeodetic (GNSS case).
  • /atteuler: publishes custom ROS message septentrio_gnss_driver/AttEuler.msg, corresponding to SBF block AttEuler.
  • /attcoveuler: publishes custom ROS message septentrio_gnss_driver/AttCovEuler.msg, corresponding to the SBF block AttCovEuler.
  • /gpst (for GPS Time): publishes generic ROS message sensor_msgs/TimeReference.msg, converted from the PVTGeodetic (GNSS case) or INSNavGeod (INS case) block's GPS time information, stored in its block header.
  • /navsatfix: publishes generic ROS message sensor_msgs/NavSatFix.msg, converted from the SBF blocks PVTGeodetic,PosCovGeodetic (GNSS case) or INSNavGeod (INS case).
  • /gpsfix: publishes generic ROS message gps_msgs/GPSFix.msg, which is much more detailed than sensor_msgs/NavSatFix.msg, converted from the SBF blocks PVTGeodetic, PosCovGeodetic, ChannelStatus, MeasEpoch, AttEuler, AttCovEuler, VelCovGeodetic, DOP (GNSS case) or INSNavGeod, DOP (INS case). In order to publish heading information, the field dip is diverted from its intended meaning an populated with the heading angle and err_dip with its uncertainty.
  • /pose: publishes generic ROS message geometry_msgs/PoseWithCovarianceStamped.msg, converted from the SBF blocks PVTGeodetic, PosCovGeodetic, AttEuler, AttCovEuler (GNSS case) or INSNavGeod (INS case).
    • Note that GNSS provides absolute positioning, while robots are often localized within a local level cartesian frame. The pose field of this ROS message contains position with respect to the absolute ENU frame (longitude, latitude, height), i.e. not a cartesian frame, while the orientation is with respect to a vehicle-fixed (e.g. for mosaic-x5 in moving base mode via the command setAttitudeOffset, ...) !local! NED frame or ENU frame if use_ros_axis_directions is set true. Thus the orientation is !not! given with respect to the same frame as the position is given in. The cross-covariances are hence set to 0.
  • /twist: publishes generic ROS message geometry_msgs/TwistWithCovarianceStamped.msg, converted from the SBF blocks PVTGeodetic and VelCovGeodetic.
  • /twist_ins: publishes generic ROS message geometry_msgs/TwistWithCovarianceStamped.msg, converted from SBF block INSNavGeod.
  • /insnavcart: publishes custom ROS message septentrio_gnss_driver/INSNavCart.msg, corresponding to SBF block INSNavCart.
  • /insnavgeod: publishes custom ROS message septentrio_gnss_driver/INSNavGeod.msg, corresponding to SBF block INSNavGeod.
  • /extsensormeas: publishes custom ROS message septentrio_gnss_driver/ExtSensorMeas.msg, corresponding to SBF block ExtSensorMeas.
  • /imusetup: publishes custom ROS message septentrio_gnss_driver/IMUSetup.msg, corresponding to SBF block IMUSetup.
  • /velsensorsetup: publishes custom ROS message septentrio_gnss_driver/VelSensorSetup.msg corresponding to SBF block VelSensorSetup.
  • /exteventinsnavcart: publishes custom ROS message septentrio_gnss_driver/INSNavCart.msg, corresponding to SBF block ExtEventINSNavCart.
  • /exteventinsnavgeod: publishes custom ROS message septentrio_gnss_driver/INSNavGeod.msg, corresponding to SBF block ExtEventINSNavGeod.
  • /diagnostics: accepts generic ROS message diagnostic_msgs/DiagnosticArray.msg, converted from the SBF blocks QualityInd, ReceiverStatus and ReceiverSetup.
  • /imu: accepts generic ROS message sensor_msgs/Imu.msg, converted from the SBF blocks ExtSensorMeas and INSNavGeod.
    • The ROS message sensor_msgs/Imu.msg can be fed directly into the robot_localization of the ROS navigation stack. Note that use_ros_axis_orientation should be set to true to adhere to the ENU convention.
  • /localization: accepts generic ROS message nav_msgs/Odometry.msg, converted from the SBF block INSNavGeod and transformed to UTM.
    • The ROS message nav_msgs/Odometry.msg can be fed directly into the robot_localization of the ROS navigation stack. Note that use_ros_axis_orientation should be set to true to adhere to the ENU convention.
  • /localization_ecef: accepts generic ROS message nav_msgs/Odometry.msg, converted from the SBF blocks INSNavCart and INSNavGeod.
    • The ROS message nav_msgs/Odometry.msg can be fed directly into the robot_localization of the ROS navigation stack. Note that use_ros_axis_orientation should be set to true to adhere to the ENU convention.

Suggestions for Improvements

Some Ideas + Equip ROSaic with an NTRIP client such that it can forward corrections to the receiver independently of `Data Link`.

Adding New SBF Blocks or NMEA Sentences

Steps to Follow Is there an SBF or NMEA message that is not being addressed while being important to your application? If yes, follow these steps: 1. Find the log reference of interest in the publicly accessible, official documentation. Hence select the reference guide file, e.g. for mosaic-x5 in the [product support section for mosaic-X5](https://www.septentrio.com/en/support/mosaic/mosaic-x5), Chapter 4, of Septentrio's homepage. 2. SBF: Add a new `.msg` file to the `../msg` folder. And modify the `../CMakeLists.txt` file by adding a new entry to the `add_message_files` section. 3. Add msg header and typedef to `typedefs.hpp`. 4. Parsers: - SBF: Add a parser to the `sbf_blocks.hpp` file. - NMEA: Construct two new parsing files such as `gpgga.cpp` to the `../src/septentrio_gnss_driver/parsers/nmea_parsers` folder and one such as `gpgga.hpp` to the `../include/septentrio_gnss_driver/parsers/nmea_parsers` folder. 5. Processing the message/block: - SBF: Extend the `SbfId` enumeration in the `message_handler.hpp` file with a new entry. - SBF: Extend the SBF switch-case in `message_handler.cpp` file with a new case. - NMEA: Extend the `nmeaMap_` in the `message_handler.hpp` file with a new pair. - NMEA: Extend the NMEA switch-case in `message_handler.cpp` file with a new case. 6. Create a new `publish/..` ROSaic parameter in the `../config/rover.yaml` file and create a boolean variable `publish_xxx` in the struct in the `settings.h` file. Parse the parameter in the `rosaic_node.cpp` file. 7. Add SBF block or NMEA to data stream setup in `communication_core.cpp` (function `configureRx()`).
CHANGELOG

Changelog for package septentrio_gnss_driver

1.3.2 (2023-11-19)

  • Commits

    : - Merge pull request #97 from thomasemter/dev/next Integrate README changes from master - Fix topics namespace - Fix units of imu angular rates - Merge upstream README pt2 - Merge upstream README - Update README.md - Update README.md - Update README.md - v1.3.1 - Updated package.xml - v1.3.1 - Updated package.xml - v1.3.1 - Updated package.xml - v1.3.1 - Updated changelog - Merge pull request #95 from thomasemter/dev/next Fix navsatfix and gpsfix frame ids - Update README.md - Fix navsatfix and gpsfix frame ids - Merge pull request #92 from thomasemter/dev/next Fix single antenna receiver setup - Update changelog - Merge - Fix single antenna receiver setup - Merge pull request #90 from thomasemter/dev/next Fix empty headers - Merge branch \'dev\' into dev/next - Bump version - Fix empty headers - Merge pull request #88 from thomasemter/dev/next Fix navsatfix containing only zeros for INS - Align indent - Fix navsatfix containig only zeros for INS - Merge pull request #87 from thomasemter/dev/next Update firmware info - Reduce INS firmware version info to released version - Update firmware info - v1.3.0 - Updated package.xml - v1.3.0 - Update firmware info - Updated package.xml - v1.3.0 - Merge pull request #84 from thomasemter/dev/next Update readme - Add expected release dates - Add known issues to readme - Update version - Update readme - Merge pull request #81 from thomasemter/dev/next Fix spelling - Improve explanations in readme - Categorize stream params - Add keep alive check for TCP - Fix spelling - Change angle wrapping - Add TCP communication via static IP server - Add units to msgs - Fix spelling - Merge pull request #75 from thomasemter/dev/next upcoming release - Add heading to GPSFix msg - Move constant - Change log level of firmware check - Add improved VSM handling - Change INS in GNSS node detection to auto - Fix invald v_x var case - Refine readme on UDP - Improve server duplicate check - Add more info un UDP configuration - Fix publish check - Add more publishing checks for configured Rx - Add const for max udp packet size - Update readme and changelog - Add device check to node - Add checks for IP server duplicates - Add latency compensation to att msgs - Add device check logic - Add UDP params and setup logic - Fix multi msg per packet - Fix localization stamp and tf publishing - Change VSM to be averaged and published with 2 Hz - Always publish raw IMU data as indicated - Change to empty fields - Refine diagnostics naming scheme and add trigger to ensure emission of ReceiverSetup - Change diagnostics naming scheme - Expand readme on AIM+ - Reformulate readme about ROS and ROS2 - Rename msg var - Add custom message to report AIM+ status - Catch invalid UTM conversion - Robustify command reset - Add RFStatus diagnostics - Merge branch \'dev/next\' of https://github.com/thomasemter/septentrio_gnss_driver into dev/next - Add VelCovCartesian output - Add VelCovCartesian output - Refine Rx type check - Ensure latency reporting block is activated - Add option for latency compensation - Fix param type misinterpretation - Add missing param to example in readme - Add OSNMA diagnostics output - Add keep_open option to OSNMA - Add OSNMA msg - Update changelog - Refine README and fix compiled message logic - Update changelog - Add warning for configuring INS as GNSS - Add warn log for misconfiguration - Fix pose publishing rate - Fix navsatfix publishing - Make vars const - Replace log functions - Add small fixes and cleanup - Merge branch \'dev/next\' of https://github.com/thomasemter/septentrio_gnss_driver into dev/next - Add option to bypass configuration of Rx - Add option to bypass confugration of Rx - Add diagnostics and time ref msgs again - Update README on how to add new messages - Add automiatic detection of serial port ID - Refine changelog - Change invalid timestamp handling for reading from file - Add USB serial by ID info to README - Fix leap seconds for timestamp if reading from file - Fix reconnection logic - Replace flow control setup - Refactor ioservice - notify semaphores in destructor - Send port reset only once - Fix serial connection - Fix talker ID setting for INS - Add NMEA talker ID setting to ensure reception - Prepare communication for UDP option (still inactive) - Fix UDP message identification logic - Add test code for UDP, WIP - Add UDP client, WIP - Set do-not-use for temp to NaN - Add processing latency correction for ROS timestamps - Fix extsensor parser - Add units to remaining msgs - Add nodiscard attribute to functions - Add nodiscard attribute to functions - Add nodiscard attribute to functions - Add const specifiers to functions - Make settings access const - Move SBF ID handling - Refactor header assembly - Rename message handler again - Change parsing utilities and crc to get message - Add namespace to enum - Change timestamp code - Update changelog - Change class privacy - Add assembled messages, to be tested - Add units to come msg definitions - Add custom BlockHeader constructor - Move wait - Remove copy paste vars - Add file readers - Fix reset main connection on exit hang - Fix handling of INS NMEA talker ID - Fix error response detection - Add packing of generic string messages - Exchange concurrent queue - Remove obsolete includes - Add NMEA handling - Change syncronization to semaphore - Add message parser, WIP - Rearrange io handling, WIP - Refactor and cleanup - Improve io handling, WIP - Refactor message parser, WIP - Add message handler - Add io modules - Add new low level interface, WIP - Change connection thread - Fix attitude cov flipped twice - Add cov alignment from true north to grid north - Rename meridian convergence and fix sense - Remove obsolete define - Fix spelling errors - Merge branch \'master\' into dev/next - v1.2.3 - Update package.xml - v1.2.3 - Update package.xml - v1.2.3 - Update package.xml - v1.2.3 - Update package.xml - Merge pull request #68 from thomasemter/master dev - Fix lat/long in rad - Reorder localization msg filling - Update readme - Fix NED to ECEF rotation matrix - Add localization ECEF publishing - Merge branch \'dev/next\' of https://github.com/thomasemter/septentrio_gnss_driver into dev/next - Merge branch \'dev/next\' of https://github.com/thomasemter/septentrio_gnss_driver into dev/next - Merge branch \'dev/next\' of https://github.com/thomasemter/septentrio_gnss_driver into dev/next - Add ecef localization msg - Add local to ecef transforms - Change default datum to Default - Clean up block data size defines - Change default datum to WGS84 - Set correct value for max number of base vector info - Add check on shutdown to only close ports on hardware - Refine readme - Merge branch \'master\' of https://github.com/thomasemter/septentrio_gnss_driver - Add missing param - Add possibility to use multiple RTK corrections of the same type - Only set baud rates on real serial ports - Fix decimal places trimming - Update changelog - Merge branch \'dev/next\' - Add base vecotr info to README - Change param to empty vector - Change param to empty vector - Fix template argument - Add quotation marks to pw if it contains spaces - Add quotation marks to pw if it contains spaces - Add option to keep aiding connections open on shutdown - Merge branch \'master\' into dev/next - Add option to keep aiding connections open on shutdown - Disable ntrip on shutdown - Disable ntrip on shutdown - Add base vector callbacks and publishing, WIP - Add base vector msgs and parsers, WIP - Fix comment swap - Add send_gga option to serial RTK and fix IP server id - Add possibility to specify IP server connection - Increase version number in package.xml and harmonize it with ROS2 - Reset main port to auto input - Add reset all used ports on shutdown - Improve readme - Change vsm options to allow simultaneous input - Change corrections settings to receiver simultaneously - Change correction options to be used simultenously - Change param name for future extensibility - Change param name for future extensibility - Rework corretion parameters and add more flexible options - Fix some spelling in readme - Add receiver type INS as GNSS - Add option to use external VSM input - Add more log output for vsm - Add VSM from odometry or twist ROS messages - Fix GPGGA and GPRMC timestamp from GNSS - Use only one stream for NMEA messages - Fix merge error - Fix merge error - Add all possible periods and rework validity check - Update changelog - Add 5 ms period option - Fix changelog - Add twist output - Add missing files to clang-formatting - Merge branch \'dev/next\' - Merge branch \'master\' of https://github.com/thomasemter/septentrio_gnss_driver - Format according to clang-format - Change log level of local frame tf insertion - Always register ReceiverSetup - Add firmware checks - Add log and info to README - Add insertion of local frame - Update README and CHANGELOG - Use leap seconds from receiver - Update changelog - Add config files for GNSS and INS - Add ReceiverTime, WIP - Add configs for GNSS and INS - Contributors: Thomas Emter, Tibor Dome, septentrio-users, tibordome

1.3.1 (2023-07-06)

  • New Features

    : - Recovery from connection interruption - Add option to bypass configuration of Rx - OSNMA - Latency compensation for ROS timestamps - Output of SBF block VelCovCartesian - Support for UDP and TCP via IP server - New VSM handling allows for unknown variances (INS firmware >= 1.4.1) - Add heading angle to GPSFix msg (by diverting dip field, cf. readme)

  • Improvements

    : - Rework IO core and message handling - Unified stream processing - Internal data queue - Prevent message loss in file reading - Add some explanatory warnings for parameter mismatches - Add units to message definitions

  • Fixes

    : - navsatfix for INS - Empty headers - Single antenna receiver setup

  • Preliminary Features

    : - Output of localization and tf in ECEF frame, testing and feedback welcome

1.2.3 (2022-11-09)

  • New Features

    : - Twist output option - Example config files for GNSS and INS - Get leap seconds from receiver - Firmware check - VSM from odometry or twist ROS messages - Add receiver type in case INS is used in GNSS mode - Add publishing of base vector topics

  • Improvements

    : - Rework RTK corrections parameters and improve flexibility

  • Fixes

    : - /tf not being published without /localization - Twist covariance matrix of localization - Support 5 ms period for IMU explicitly

1.1.2 (2022-06-22)

  • Fixes

    : - Memory corruption under adverse conditions

1.1.1 (2022-05-16)

  • New Features

    : - Add login credentials - Activate NTP server if use_gnss_time is set to true

  • Improvements

    : - Add NED option to localization

  • Fixes

    : - IMU orientation for ROS axis convention

  • Commits

    : - Merge pull request #62 from thomasemter/dev/next Small fixes and additions - Amend readme regarding robot_localization - Add more explanations for IMU orientation in ROS convention - Fix formatting in readme - Fix package name in readme - Update readme - Update changelog - Fix IMU orientation for ROS axis orientation - Activate NTP only if GNSS time is used - Add NED option to localization - Set NMEA header to - Fix logging causing crash - Update readme and changelog - Activate NTP server - Add credentials for access control - Contributors: Thomas Emter, Tibor Dome

1.1.0 (2022-04-25)

  • New Features

    : - Add option to use ROS axis orientations according to REP103 - Add frame_id parameters - Add option to get frames from tf - Publishing of cartesian localization in UTM (topic and/or tf) for INS - Publishing of IMU topic for INS - Publishing of MeasEpoch - ROS2 branch

  • Improvements

    : - Add multi antenna option - Increase number of SBF streams - Add option to set polling_period to \"on change\" - Increased buffer size from 8192 to 131072 bytes - Add endianess aware parsers - Only publish topics set to true - Add parameter to switch DEBUG logging on and off - Change GPxxx messages to ROS built-in types - Remove duplicate INS msg types

  • Fixes

    : - Setting of antenna type - Publishing rate interconnections of gpsfix and velcovgeodetic - Missing quotes for antenna type - Broken attitude parsing pose and gpsfix from INS - IMU orientation was not sent to Rx - Graceful shutdown of threads

  • Commits

    : - Merge branch \'dev\' - Prepare new release - Prepare new release - Merge pull request #53 from thomasemter/dev/refactor Very last changes - Add geographic lib dependency to package.xml - Add comment for frame of main antenna - Move utm zone locking section in readme - Reformulate readme section on frames - Merge pull request #52 from thomasemter/dev/refactor Last changes - Change frame id back to poi_frame_id - Make error log more explicit - Merge pull request #49 from thomasemter/dev/refactor Improve IMU blocks sync and do-not-use value handling - Fix buffer size in changelog - Turn off Nagle\'s algorithm for TCP - Fix changelog formatting - Fix readme - Set default base frame to base_link - Fix valid tow check logic - Increase buffer size for extreme stress tests - Fix crc check - Fix and streamline tf handling - Add checks for validity of values - Fix rad vs deg - Update changelog - Add some comments - Set stdDevMask to values > 0.0 in node - Set stdDevMask to values > 0.0 - Add info on RNDIS and set it to default - Increase default serial baud rate - Add parameter to set log level to debug - Change defaults for publishers in node - Put publish params together and fix mismatch in readme - Improve IMU blocks sync and do-not-use value handling - Merge pull request #48 from thomasemter/dev/refactor Fix measepoch not publishing without gpsfix - Fix measepoch not publishing without gpsfix - Merge pull request #47 from thomasemter/dev/refactor Dev/refactor - Publish only messages set to true - Remove leftover declaration - Merge branch \'dev/endianess_agnostic\' into dev/refactor - Update readme to reflect endianess aware parsing - Remove msg smart pointers - Fix array assertion failure - Cleanup - Add ReceiverStatus parser - Add QualityInd parser - Add DOP parser - Add ReceiverSetup parser - Fix MeasEpoch and ChannelStatus parsers, add measepoch publishing - Add ChannelStatus parser - Add MeasEpoch parser - Add IMU and VelSensor setup parsers - Add Cov SBF parsers - Add templated qi parser function - Add AttEuler+Cov parser - Revert ordering change inside INSNav ROS msgs - Add ExtSensorMeas parser - Add PVT parsers - Add range checks to parsers - Replace INSNav grammar with parsers - Test parser vs. grammar for better performance - Fix sb_list check - Add IMU and VelSensor setup grammars - Move adapt ROS header to typedefs.h - Add revision check to MeasEpoch - Fix ReceiverStatus grammar - Extend ReceiverSetup and add revision checks - Change logger and fix loop range - Remove reserved bytes from parsing - Remove obsolete structs - Directly parse Cov SBFs to ROS msg - Directly parse PVT SBFs, remove obsolete ids - Rename rev to revision - Fix block header parsing - Directly parse AttEuler to ROS msg - Directly parse to ROS msgs for INSNavXxx - Exchange pow with square function and remove casts - Merge pull request #46 from thomasemter/dev/refactor Dev/refactor - Simplify sync bytes check - Move tow/wnc to BlockHeader - Adjust order in INSNav ros msgs - Fix INSNav grammars - Change BlockHeader structure - Remove length ref from header - Rectify sb_list check of INSNavXxx - Add automtatic activation of multi-antenna mode - Merge branch \'dev/refactor\' of https://github.com/thomasemter/septentrio_gnss_driver into dev/refactor - Add automtatic activation of multi-antenna mode - Fix wrong scope of phoenix::ref variables - Fix AttEuler grammar - Add max size checks to QualityInd and ReceiverStatus - Replace locals with phoenix::ref in grammars - Add revision dependent parsing to PVTs - Change offset check to epsilon - Change offset check to epsilon - Fix parsing checks - Set has arrived to false on parsing error - Add INSNav grammars - Add abs to offset check - Add abs to offset check - Add Cov grammars - Remove superfluous typdefs of structs - Add ReceiverStatus grammar - Add QualityINd grammar - Merge pull request #45 from thomasemter/dev/refactor Dev/refactor - Add id check to header grammar - Add id check to header grammar - Add ReceiverSetup grammar - Add DOP grammar - Directly intialize vector to parse - Add MeasEpoch grammar - Remove duplicate msg types - Remove obsolete include - Add revision and length return to header grammar - Merge branch \'feature/endianess_agnostic\' into dev/endianess_agnostic - Make multi_antenna option also usable for gnss - Add typedefs plus some minor changes - Add warning concerning pitch angle if antennas are rotated - Add multi antenna option to ins and fix antenna offset decimal places trimming - Fix identation - Distinguish between gnss and ins for spatial config from tf - Merge pull request #43 from thomasemter/dev/refactor Dev/refactor - Add vehicle frame for clarity - Handle missing tf more gently - Merge branch \'dev/spatial_config_via_tf\' into dev/refactor - Update readme - Fix antenna offset from tf - Add automatic publishing of localization if tf is activated - Add automatic publishing of localization if tf is activated - Add spatial config via tf, to be tested - Fix crashes due to parsing errors (replacing uncatched throws) - Add tf broadcasting - Add comments - Add localization in UTM output - Add check to IMU msg sync - Change msg sync to allow for 200 Hz IMU msgs - Add ROS IMU msg - Fix IMU setup message attitude conversion - Fix pose from INS data - Fix IMU raw data rotation compensation - Make antenna attitude offset usable by GNSS - Add ros directions option to pose and fix covariances - Update readme - Merge branch \'feature/ros_axis_orientation\' into dev/refactor - Add nmea_msgs dependencies - Merge branch \'dev/nmea\' into dev/refactor - Update readme - Update readme - Add antenna offsets to conversions - Fix IMU orientation conversion - Change ExtSensorMead temperature to deg C - Add axis orientation info to readme - Fix IMU axis orientation - Change get int param - Update readme to reflect removal of aux antenna offset - Fix different antenna setup message for INS and remove obsolete aux1 antenna offset for GNSS - Fix ExtSensorMeas message filling - Fix ExtSensorMeas message to reflect available fields - Fix missing INS blocks - Fix missing INS blocks - WIP, introduce ros axis orientation option, to be tested - Add option to set pvt rate to OnChange - Add comment on NTP to readme - Change to nmea_msgs - Add automatic addition of needed sub messages - Comment out setting debug level - Add comments and fix spelling errors - Merge pull request #42 from thomasemter/dev/refactor Dev/refactor - Change to quaternion msg typedef - Comment out debug logging - Remove filling of seq field - Change msg definitions to be compatible with ROS2 - Update readme - Change make_shared for portability and add more typedefs - Add get param int fallback for numeric antenna serial numbers - Change Attitude to be published with pvt rate - Add log identifier - Add checks for relevant ros params - Concatenate multiple SBF blocks in streams - Move main into own file - Move get ros time to AsyncManager - Remove obsolete param comment - Move get ros params to base class - Change to nsec timestamp internally - Add publishing functionality to node base class - Move node handle ptr and functions to base class and rename - Add stamp to nmea parsing - Add logging in PcapReader - Add logging in CircularBuffer - Add missed logging - Add logging in AsyncManager - Add getTime function - Add logging in RxMessage - Add logging in CallbackHandlers - Add log function to node by polymorphism, logging in Comm_OI - Fix wait function and force use_gnss_time when reading from file - Add thread shutdown and remove spurious delete - Add typedefs for ins messages - Add typedefs for gnss messages - Add typedefs for ros messages - Refine shutdown - Fix shutdown escalating to SIGTERM - Move waiting for response in send function - Make functions private - Change crc to C++ - Fix variable name - Remove global variables from node cpp file - Move more global settings to settings struct - Move more global settings to settings struct - Move global settings to settings struct - Move more functions to CommIo - Move settings to struct and configuration to CommIo - Merge branch \'dev/change_utc_calculation\' into dev/refactor - Remove obsolete global variables - Move g_unix_time to class - Make has_arrived booleans class memebers and rx_message a persistent class - Make node handle a class member - Fix parsing of ID and rev - Finish ChannelStatusGrammar, to be tested - WIP, partially fix ChannelStatusGrammar - Add SBF length parsing utility - Insert spirit parsers - WIP, add omission of padding bytes - WIP, add more spirit parsers - Add parsing utilities for tow, wnc and ID - Move getId/Tow/Wnc to parsing utilities - Change UTC calculation to use tow and wnc - WIP, add boost spirit and endian buffers - Change UTC calculation to use tow and wnc

  • Update Readme and Changelog

  • Contributors: Thomas Emter, Tibor Dome

1.0.8 (2021-10-23)

  • Added INS Support

1.0.7 (2021-05-18)

  • Clang formatting, publishing from SBF log, play-back of PCAP files

1.0.6 (2020-10-16)

  • ROSaic binary installation now available on Melodic & Noetic

1.0.5 (2020-10-15)

  • changed repo name
  • v1.0.4
  • 1.0.3
  • Merge pull request #22 from septentrio-gnss/local_tibor New changelog
  • New changelog
  • Merge pull request #21 from septentrio-gnss/local_tibor Added rosdoc.yaml file
  • Merge pull request #20 from septentrio-gnss/local_tibor Improved doxygen annotations
  • Merge pull request #19 from septentrio-gnss/local_tibor Improved doxygen annotations
  • Update README.md
  • Merge pull request #18 from septentrio-gnss/local_tibor Adopted ROS and C++ conventions, added ROS diagnostics msg,
  • Update README.md
  • Update README.md
  • Update README.md
  • Contributors: septentrio-users, tibordome

1.0.4 (2020-10-11)

  • Added rosdoc.yaml file
  • Improved doxygen annotations
  • Improved doxygen annotations
  • Adopted ROS and C++ conventions, added ROS diagnostics msg, removed ROS garbage value bug, added auto-detection of SBF arrival order for composite ROS msgs
  • Merge branch \'master\' of https://github.com/septentrio-gnss/rosaic
  • NTRIP with Datalink, circular buffer, reading connection descriptor, new messages
  • Update README.md
  • Contributors: septentrio-users, tibordome

1.0.3 (2020-09-30)

  • Add new config/rover.yaml file
  • Add config/rover.yaml to .gitignore
  • Merge pull request #17 from septentrio-gnss/local_tibor NTRIP with Datalink, circular buffer, reading connection descriptor..
  • Merge branch \'local_tibor\'
  • NTRIP with Datalink, circular buffer, reading connection descriptor, new messages
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #16 from septentrio-gnss/local_tibor NTRIP parameters added, reconnect_delay_s implemented,
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #15 from tibordome/local_tibor GPSFix completed, datum as new parameter
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #14 from tibordome/local_tibor GPSFix completed, datum as new parameter
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #13 from tibordome/local_tibor Added AttCovEuler.msg and AttEuler.msg
  • Merge pull request #12 from tibordome/local_tibor Fixed service field of NavSatStatus
  • Contributors: Tibor Dome, septentrio-users, tibordome

1.0.2 (2020-09-25)

  • NTRIP parameters added, reconnect_delay_s implemented, package.xml updated, ROSaic now detects connection descriptor automatically, mosaic serial port parameter added
  • GPSFix completed, datum as new parameter, ANT type and marker-to-arp distances as new parameters, BlockLength() method corrected, sending multiple commands to Rx corrected by means of mutex
  • Contributors: tibordome

1.0.1 (2020-09-22)

  • GPSFix completed, datum as new parameter, ANT type and marker-to-arp distances as new parameters, BlockLength() method corrected, sending multiple commands to Rx corrected by means of mutex
  • Added AttCovEuler.msg and AttEuler.msg
  • Fixed service field of NavSatStatus, fixed ROS header\'s seq field of each published ROS message, added write method for sending commands to Rx, successfully tested, added AttEuler, added AttCovEuler
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #11 from tibordome/local_tibor rosconsole_backend_interface dependency not needed
  • rosconsole_backend_interface dependency not needed
  • Merge pull request #10 from tibordome/local_tibor rosconsole_log4cxx dep not needed
  • rosconsole_log4cxx dep not needed
  • Merge pull request #9 from tibordome/local_tibor rosconsole_log4cxx dep not needed
  • rosconsole_log4cxx dep not needed
  • Merge pull request #8 from tibordome/local_tibor Local tibor
  • Update README.md
  • Merge pull request #7 from tibordome/local_tibor Ready for First Release
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #6 from tibordome/local_tibor Local tibor
  • Merge pull request #5 from tibordome/local_tibor TCP seems to work
  • Contributors: Tibor Dome, tibordome

1.0.0 (2020-09-11)

  • Ready for first release
  • Added Gpgga.msg and PosCovGeodetic.msg files
  • Ready for First Release
  • Ready for first release
  • Ready for first release
  • Ready for first release
  • TCP bug removed
  • TCP bug removed
  • TCP seems to work
  • Merge pull request #4 from tibordome/v0.2 V0.2
  • PVTCartesian and PVTGeodetic publishing works on serial
  • PVTCartesian and PVTGeodetic publishing works on serial
  • Merge pull request #3 from tibordome/v0.2 Add doxygen_out and Doxyfile 2nd trial
  • Add doxygen_out and Doxyfile 2nd trial
  • Merge pull request #2 from tibordome/v0.1 Add doxygen_out and Doxyfile
  • Add doxygen_out and Doxyfile
  • Update README.md
  • Create README.md
  • Update LICENSE
  • Merge pull request #1 from tibordome/add-license-1 Create LICENSE
  • Create LICENSE
  • Create LICENSE
  • Commit
  • Successfully tested publishing to /gpgga topic via serial
  • To make sure master branch exists
  • Contributors: Tibor Dome, tibordome

Wiki Tutorials

See ROS Wiki Tutorials for more details.

Source Tutorials

Not currently indexed.

Recent questions tagged septentrio_gnss_driver at Robotics Stack Exchange

septentrio_gnss_driver package from septentrio_gnss_driver repo

septentrio_gnss_driver

Package Summary

Tags No category tags.
Version 1.3.2
License BSD 3-Clause License
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/septentrio-gnss/septentrio_gnss_driver.git
VCS Type git
VCS Version ros2
Last Updated 2023-11-22
Dev Status MAINTAINED
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

ROSaic: C++ driver for Septentrio's mosaic receivers and beyond

Additional Links

Maintainers

  • Tibor Dome
  • Septentrio

Authors

  • Tibor Dome

ROSaic = ROS + mosaic

Overview

This repository hosts drivers for ROS (Melodic and Noetic) and ROS 2 (Foxy, Galactic, Humble, Rolling, and beyond) - written in C++ - that work with mosaic and AsteRx - two of Septentrio's cutting-edge GNSS and GNSS/INS receiver families - and beyond. The ROS 2 version is available in this branch, whereas the ROS 1 version is available in the branch master.

Main Features: - Supports Septentrio's single antenna GNSS, dual antenna GNSS and INS receivers - Supports serial, TCP/IP and USB connections, the latter being compatible with both serial (RNDIS) and TCP/IP protocols - Supports several ASCII (including key NMEA ones) messages and SBF (Septentrio Binary Format) blocks - Reports status of AIM+ (Advanced Interference Mitigation including OSNMA) anti-jamming and anti-spoofing. - Can publish nav_msgs/Odometry message for INS receivers - Can blend SBF blocks PVTGeodetic, PosCovGeodetic, ChannelStatus, MeasEpoch, AttEuler, AttCovEuler, VelCovGeodetic and DOP in order to publish gps_common/GPSFix and sensor_msgs/NavSatFix messages - Supports axis convention conversion as Septentrio follows the NED convention, whereas ROS is ENU. - Easy configuration of multiple RTK corrections simultaneously (via NTRIP, TCP/IP stream, or serial) - Can play back PCAP capture logs for testing purposes - Tested with the mosaic-X5, mosaic-H, AsteRx-m3 Pro+ and the AsteRx-SBi3 Pro receiver - Easy to add support for more log types

Please let the maintainers know of your success or failure in using the driver with other devices so we can update this page appropriately.

Dependencies

The ros2 branch for this driver functions on ROS Foxy, Galactic, Rolling, and Humble (Ubuntu 20.04 or 22.04 respectively). It is thus necessary to install the ROS version that has been designed for your Linux distro.

Additional ROS packages have to be installed for the NMEA and GPSFix messages.

sudo apt install ros-$ROS_DISTRO-nmea-msgs ros-$ROS_DISTRO-gps-msgs.

The serial and TCP/IP communication interface of the ROS driver is established by means of the Boost C++ library. In the unlikely event that the below installation instructions fail to install Boost on the fly, please install the Boost libraries via

sudo apt install libboost-all-dev.

Compatiblity with PCAP captures are incorporated through pcap libraries. Install the necessary headers via

sudo apt install libpcap-dev.

Conversions from LLA to UTM are incorporated through GeographicLib. Install the necessary headers via

sudo apt install libgeographic-dev

Usage

Binary Install The binary release is now available for Foxy and Galactic. To install the binary package, simply run `sudo apt-get install ros-$ROS_DISTRO-septentrio-gnss-driver`.
Build from Source The package has to be built from source using [`colcon`](https://docs.ros.org/en/humble/Tutorials/Beginner-Client-Libraries/Colcon-Tutorial.html): ``` source /opt/ros/${ROS_DISTRO}/setup.bash # In case you do not use the default shell of Ubuntu, you need to source another script, e.g. setup.sh. mkdir -p ~/septentrio/src # Note: Change accordingly depending on where you want your package to be installed. cd ~/septentrio/src git clone https://github.com/septentrio-gnss/septentrio_gnss_driver git checkout ros2 # Install mentioned dependencies (`sudo apt install ros-$ROS_DISTRO-nmea_msgs ros-$ROS_DISTRO-gps-msgs libboost-all-dev libpcap-dev libgeographic-dev`) colcon build --packages-up-to septentrio_gnss_driver # Be sure to call colcon build in the root folder of your workspace. Launch files are installed, so changing them on the fly in the source folder only works with installing by symlinks: add `--symlink-install` echo "source ~/septentrio/devel/setup.bash" >> ~/.bashrc # It is convenient if the ROS environment variable is automatically added to your bash session every time a new shell is launched. Again, this works for bash shells only. Also note that if you have more than one ROS distribution installed, ~/.bashrc must only source the setup.bash for the version you are currently using. source ~/.bashrc ``` Run tests ``` colcon test --packages-select septentrio_gnss_driver --event-handlers console_direct+ ```
Notes Before Usage + In your bash sessions, navigating to the ROSaic package can be achieved from anywhere with no more effort than `roscd septentrio_gnss_driver`. + The driver assumes that our anonymous access to the Rx grants us full control rights. This should be the case by default, and can otherwise be changed with the `setDefaultAccessLevel` command. If user control is in place user credentials can be given by parameters `login.user` and `login.password`. + ROSaic only works from C++17 onwards due to std::any() etc. + Note for setting hw_flow_control: This is a string parameter, setting it to off without quotes leads to the fact that it is not read in correctly. + Note for setting ant_(aux1)_serial_nr: This is a string parameter, numeric only serial numbers should be put in quotes. If this is not done a warning will be issued and the driver tries to parse it as integer. + Once the colcon build or binary installation is finished, adapt the `config/rover.yaml` file according to your needs or assemble a new one. Launch as composition with `ros2 launch septentrio_gnss_driver rover.launch.py` to use `rover.yaml` or add `file_name:=xxx.yaml` to use a custom config. Alternatively launch as node with `ros2 launch septentrio_gnss_driver rover_node.launch.py` to use `rover_node.yaml` or add `file_name:=xxx.yaml` to use a custom config. Specify the communication parameters, the ROS messages to be published, the frequency at which the latter should happen etc. + Besides the aforementioned config file `rover.yaml` containing all parameters, specialized launch files for GNSS `config/gnss.yaml` and INS `config/ins.yaml` respectively contain only the relevant parameters in each case. - NOTE: Unless `configure_rx` is set to `false`, this driver will overwrite the previous values of the parameters, even if the value is left to zero in the "yaml" file. + The driver was developed and tested with firmware versions >= 4.10.0 for GNSS and >= 1.3.2 for INS. Receivers with older firmware versions are supported but some features may not be available. Known limitations are: * GNSS with firmware < 4.10.0 does not support IP over USB. * GNSS with firmware < 4.12.1 does not support OSNMA. * INS with firmware < 1.3.2 does not support NTP. * INS with firmware < 1.4 does not support OSNMA. * INS with firmware < 1.4.1 does not support improved VSM handling allowing for unknown variances. * INS with firmware 1.2.0 does not support velocity aiding. * INS with firmware 1.2.0 does not support setting of initial heading. + Known issues: * UDP over USB: Blocks are sent twice on GNSS with firmware <= 4.12.1 and INS with firmware <= 1.4. For GNSS it is fixed in version 4.14 (released on June 15th 2023), for INS it will be fixed in to-be-released 1.4.1 (expected in November 2023). + If `use_ros_axis_orientation` to `true` axis orientations are converted by the driver between NED (Septentrio: yaw = 0 is north, positive clockwise) and ENU (ROS: yaw = 0 is east, positive counterclockwise). There is no conversion when setting this parameter to `false` and the angles will be consistent with the web GUI in this case. :
``` # Example configuration Settings for the Rover Rx device: tcp://192.168.3.1:28784 serial: baudrate: 921600 hw_flow_control: "off" tcp: ip_server: "" port: 0 udp: ip_server: "" port: 0 unicast_ip: "" configure_rx: true login: user: "" password: "" osnma: mode: "off" ntp_server: "" keep_open: true frame_id: gnss imu_frame_id: imu poi_frame_id: base_link vsm_frame_id: vsm aux1_frame_id: aux1 vehicle_frame_id: base_link insert_local_frame: false local_frame_id: odom get_spatial_config_from_tf: true lock_utm_zone: true use_ros_axis_orientation: true receiver_type: gnss datum: Default poi_to_arp: delta_e: 0.0 delta_n: 0.0 delta_u: 0.0 att_offset: heading: 0.0 pitch: 0.0 ant_type: Unknown ant_aux1_type: Unknown ant_serial_nr: Unknown ant_aux1_serial_nr: Unknown leap_seconds: 18 polling_period: pvt: 500 rest: 500 use_gnss_time: false latency_compensation: false rtk_settings: ntrip_1: id: "NTR1" caster: "1.2.3.4" caster_port: 2101 username: "Asterix" password: "password" mountpoint: "mtpt1" version: "v2" tls: true fingerprint: "AA:BB:56:78:90:12: ... 78:90:12:34" rtk_standard: "RTCMv3" send_gga: "auto" keep_open: true ntrip_2: id: "NTR3" caster: "5.6.7.8" caster_port: 2101 username: "Obelix" password: "password" mountpoint: "mtpt2" version: "v2" tls: false fingerprint: "" rtk_standard: "RTCMv2" send_gga: "auto" keep_open: true ip_server_1: id: "IPS3" port: 28785 rtk_standard: "RTCMv2" send_gga: "auto" keep_open: true ip_server_2: id: "IPS5" port: 28786 rtk_standard: "CMRv2" send_gga: "auto" keep_open: true serial_1: port: "COM1" baud_rate: 230400 rtk_standard: "auto" send_gga: "sec1" keep_open: true serial_2: port: "COM2" baud_rate: 230400 rtk_standard: "auto" send_gga: "off" keep_open: true publish: # For both GNSS and INS Rxs navsatfix: false gpsfix: true gpgga: false gprmc: false gpst: false measepoch: false pvtcartesian: false pvtgeodetic: true basevectorcart: false basevectorgeod: false poscovcartesian: false poscovgeodetic: true velcovcartesian: false velcovgeodetic: false atteuler: true attcoveuler: true pose: false twist: false diagnostics: false aimplusstatus: true galauthstatus: false # For GNSS Rx only gpgsa: false gpgsv: false # For INS Rx only insnavcart: false insnavgeod: false extsensormeas: false imusetup: false velsensorsetup: false exteventinsnavcart: false exteventinsnavgeod: false imu: false localization: false tf: false localization_ecef: false tf_ecef: false # INS-Specific Parameters ins_spatial_config: imu_orientation: theta_x: 0.0 theta_y: 0.0 theta_z: 0.0 poi_lever_arm: delta_x: 0.0 delta_y: 0.0 delta_z: 0.0 ant_lever_arm: x: 0.0 y: 0.0 z: 0.0 vsm_lever_arm: vsm_x: 0.0 vsm_y: 0.0 vsm_z: 0.0 ins_initial_heading: auto ins_std_dev_mask: att_std_dev: 5.0 pos_std_dev: 10.0 ins_use_poi: true ins_vsm: source: "twist" config: [true, false, false] variances_by_parameter: true variances: [0.1, 0.0, 0.0] ip_server: id: "IPS2" port: 28787 keep_open: true serial: port: "COM3" baud_rate: 115200 keep_open: true # Logger activate_debug_log: false ``` In order to launch ROSaic, one must specify all `arg` fields of the `rover.py` file which have no associated default values, i.e. for now only the `file_name` field. Hence, the launch command reads `ros2 launch septentrio_gnss_driver rover.py file_name:=rover.yaml`. If multiple port are utilized for RTK corrections and/or VSM, which shall be closed after driver shutdown (`keep_open: false`), make sure to give the driver enough time to gracefully shutdown as closing the ports takes a few seconds. This can be accomplished in the launch files by increasing the timeout of SIGTERM (e.g. `sigterm_timeout = '10',`), see example launch files`rover.py`and `rover_node.py` respectively.

Inertial Navigation System (INS): Basics

  • An Inertial Navigation System (INS) is a device which takes the rotation and acceleration solutions as obtained from its Inertial Measurement Unit (IMU) and combines those with position and velocity information from the GNSS module. Compared to a GNSS system with 7D or 8D (dual-antenna systems) phase space solutions, the combined, Kalman-filtered 9D phase space solution (3 for position, 3 for velocity, 3 for orientation) of an INS is more accurate, more precise and more stable against GNSS outages.
  • The IMU is typically made up of a 3-axis accelerometer, a 3-axis gyroscope and sometimes a 3-axis magnetometer and measures the system's angular rate and acceleration.

    Measure and Compensate for IMU-Antenna Lever Arm

    • The IMU-antenna lever-arm is the relative position between the IMU reference point and the GNSS Antenna Reference Point (ARP), measured in the vehicle frame.
    • In case of AsteRx SBi3, the IMU reference point is clearly marked on the top panel of the receiver. It is important to compensate for the effect of the lever arm, otherwise the receiver may not be able to calculate an accurate INS position.
    • The IMU/antenna position can be changed by specifying the lever arm's x,yand z parameters in the config.yaml file under the ins_spatial_config.ant_lever_arm parameter.

    Screenshot from 2021-08-03 09-23-19 (1)

    Compensate for IMU Orientation + It is important to take into consideration the mounting direction of the IMU in the body frame of the vehicle. For e.g. when the receiver is installed horizontally with the front panel facing the direction of travel, we must compensate for the IMU’s orientation to make sure the IMU reference frame is aligned with the vehicle reference frame. The IMU position and orientation is printed on the top panel, cf. image below. + The IMU's orientation can be changed by specifying the orientation angles theta_x,theta_yand theta_z in the config.yaml file under ins_spatial_config.imu_orientation + The below image illustrates the orientation of the IMU reference frame with the associated IMU orientation for the depicted installation. Note that for use_ros_axis_orientation: true sensor_default is the top left position.

    Capture (1)

  • These Steps should be followed to configure the receiver in INS integration mode:

    • Specify receiver_type: INS
    • Specify the orientation of the IMU sensor with respect to your vehicle, using the ins_spatial_config.imu_orientation parameter.
    • Specify the IMU-antenna lever arm in the vehicle reference frame. This is the vector starting from the IMU reference point to the ARP of the main GNSS antenna. This can be done by means of the ins_spatial_config.ant_lever_arm parameter.
    • Specify ins_spatial_config.vsm_lever_arm if measurements of a velocity sensor is available.
    • Alternatively the lever arms may be specified via tf. Set get_spatial_config_from_tfto true in this case.
    • If the point of interest is neither the IMU nor the ARP of the main GNSS antenna, the vector between the IMU and the point of interest can be provided with the ins_solution/poi_lever_arm parameter.
  • For further more information about Septentrio receivers, visit Septentrio support resources or check out the user manual and reference guide of the AsteRx SBi3 receiver.

ROSaic Parameters

The following is a list of ROSaic parameters found in the config/rover.yaml file. * Parameters Configuring Communication Ports and Processing of GNSS and INS Data

Connectivity Specs

  • device: location of main device connection. This interface will be used for setup communication and VSM data for INS. Incoming data streams of SBF blocks and NMEA sentences are recevied either via this interface or a static IP server for TCP and/or UDP. The former will be utilized if section stream_device.tcp and stream_device.udp are not configured.
    • serial:xxx format for serial connections,where xxx is the device node, e.g. serial:/dev/ttyS0. If using serial over USB, it is recommended to specify the port by ID as the Rx may get a different ttyXXX on reconnection, e.g. serial:/dev/serial/by-id/usb-Septentrio_Septentrio_USB_Device_xyz.
    • file_name:path/to/file.sbf format for publishing from an SBF log
    • file_name:path/to/file.pcap format for publishing from PCAP capture.
      • Regarding the file path, ROS_HOME=`pwd` in front of roslaunch septentrio... might be useful to specify that the node should be started using the executable's directory as its working-directory.
    • tcp://host:port format for TCP/IP connections
      • 28784 should be used as the default (command) port for TCP/IP connections. If another port is specified, the receiver needs to be (re-)configured via the Web Interface before ROSaic can be used.
      • An RNDIS IP interface is provided via USB, assigning the address 192.168.3.1 to the receiver. This should work on most modern Linux distributions. To verify successful connection, open a web browser to access the web interface of the receiver using the IP address 192.168.3.1.
    • default: tcp://192.168.3.1:28784
  • serial: specifications for serial communication
    • baudrate: serial baud rate to be used in a serial connection. Ensure the provided rate is sufficient for the chosen SBF blocks. For example, activating MeasEpoch (also necessary for /gpsfix) may require up to almost 400 kBit/s.
    • rx_serial_port: determines to which (virtual) serial port of the Rx we want to get connected to, e.g. USB1 or COM1
    • hw_flow_control: specifies whether the serial (the Rx's COM ports, not USB1 or USB2) connection to the Rx should have UART hardware flow control enabled or not
      • off to disable UART hardware flow control, RTS|CTS to enable it
    • default: 921600, USB1, off
  • stream_device: If left unconfigured, by default device is utilized for the data streams. Within stream_device static IP servers may be defined instead. In config mode (configure_rx set to true), TCP will be prioritized over UDP. If Rx is pre-configured, both may be set simultaneously.
    • tcp: specifications for static TCP server of SBF blocks and NMEA sentences.
      • ip_server: IP server of Rx to be used, e.g. “IPS1”.
      • port: UDP destination port.
    • udp: specifications for low latency UDP reception of SBF blocks and NMEA sentences.
      • ip_server: IP server of Rx to be used, e.g. “IPS1”.
      • port: UDP destination port.
      • unicast_ip: Set to computer's IP to use unicast (optional). If not set multicast will be used.
  • login: credentials for user authentication to perform actions not allowed to anonymous users. Leave empty for anonymous access.
    • user: user name
    • password: password

OSNMA

  • osnma: Configuration of the Open Service Navigation Message Authentication (OSNMA) feature.
    • mode: Three operating modes are supported: off where OSNMA authentication is disabled, loose where satellites are included in the PVT if they are successfully authenticated or if their authentication status is unknown, and strict where only successfully-authenticated satellites are included in the PVT. In case of strict synchronization via NTP is mandatory.
      • default: off
    • ntp_server: In strict mode, OSNMA authentication requires the availability of external time information. In loose mode, this is optional but recommended for enhanced security. The receiver can connect to an NTP time server for this purpose. Options are default to let the receiver choose an NTP server or specify one like pool.ntp.org for example.
      • default: ""
    • keep_open: Wether OSNMA shall be kept active on driver shutdown.
      • default: true

Receiver Configuration

+ configure_rx: Wether to configure the Rx according to the config file. If set to `false`, the Rx has to be configured via the web interface and the settings must be saved. On the driver side communication has to set accordingly to serial, TCP or UDP (TCP and UDP may even be used simultaneously in this case). For TCP communication it is recommended to use a static TCP server (`stream_device.tcp.ip_server` and `stream_device.tcp.port`), since dynamic connections (`device` is tcp) are not guaranteed to have the same id on reconnection. It should also be ensured that obligatory SBF blocks are activated (as of now: ReceiverTime if `use_gnss_time` is set to `true`; `PVTGeodetic`or `PVTCartesian` if latency compensation for PVT related blocks shall be used). Further, if ROS messages compiled from multiple SBF blocks, it should be ensured that all necessary blocks are activated with matching periods, details can be found in section [ROS Topic Publications](#ros-topic-publications). The messages that shall be published still have to be set to `true` in the *NMEA/SBF Messages to be Published* section. Also, parameters concerning the connection and node setup are still relevant (sections: *Connectivity Specs*, *receiver type*, *Frame IDs*, *UTM Zone Locking*, *Time Systems*, *Logger*).
  + default: true

Receiver Type

  • receiver_type: This parameter is to select the type of the Septentrio receiver
    • gnss for GNSS receivers.
    • ins for INS receivers.
    • default: gnss
  • multi_antenna: Whether or not the Rx has multiple antennas.
    • default: false

Frame IDs

  • frame_id: name of the ROS tf frame for the Rx, placed in the header of published GNSS messages. It corresponds to the frame of the main antenna.
    • In ROS, the tf package lets you keep track of multiple coordinate frames over time. The frame ID will be resolved by tf_prefix if defined. If a ROS message has a header (all of those we publish do), the frame ID can be found via rostopic echo /topic, where /topic is the topic into which the message is being published.
    • default: gnss
  • imu_frame_id: name of the ROS tf frame for the IMU, placed in the header of published IMU message
    • default: imu
  • poi_frame_id: name of the ROS tf frame for the POI, placed in the child frame_id of localization if ins_use_poi is set to true.
    • default: base_link
  • vsm_frame_id: name of the ROS tf frame for the velocity sensor.
    • default: vsm
  • aux1_frame_id: name of the ROS tf frame for the aux1 antenna.
    • default: aux1
  • vehicle_frame_id: name of the ROS tf frame for the vehicle. Default is the same as poi_frame_id but may be set otherwise.
    • default: base_link
  • local_frame_id: name of the ROS tf frame for the local frame.
    • default: odom
  • insert_local_frame: Wether to insert a local frame to published tf according to ROS REP 105. The transform from the local frame specified by local_frame_id to the vehicle frame specified by vehicle_frame_id has to be provided, e.g. by odometry. Insertion of the local frame means the transform between local frame and global frame is published instead of transform between vehicle frame and global frame.
    • default: false
  • get_spatial_config_from_tf: wether to get the spatial config via tf with the above mentioned frame ids. This will override spatial settings of the config file. For receiver type ins with multi_antenna set to true all frames have to be provided, with multi_antenna set to false, aux1_frame_id is not necessary. For type gnss with dual-antenna setup only frame_id, aux1_frame_id, and poi_frame_id are needed. For single-antenna gnss no frames are needed. Keep in mind that tf has a tree structure. Thus, poi_frame_id is the base for all mentioned frames.
    • default: false
  • use_ros_axis_orientation Wether to use ROS axis orientations according to ROS REP 103 for body related frames and geographic frames. Body frame directions affect INS lever arms and IMU orientation setup parameters. Geographic frame directions affect orientation Euler angles for INS+GNSS and attitude of dual-antenna GNSS. If use_ros_axis_orientation is set to true, the driver converts between the NED convention (Septentrio: yaw = 0 is north, positive clockwise), and ENU convention (ROS: yaw = 0 is east, positive counterclockwise). There is no conversion when setting this parameter to false and the angles will be consistent with the web GUI in this case.
    • If set to false Septentrios definition is used, i.e., front-right-down body related frames and NED (north-east-down) for orientation frames.
    • If set to true ROS definition is used, i.e., front-left-up body related frames and ENU (east-north-up) for orientation frames.
    • default: true

UTM zone locking + lock_utm_zone: wether the UTM zone of the initial localization is locked, i.e., this zone is kept even if a zone transition would occur. + default: true

Datum

  • datum: With this command, the datum the coordinates should refer to is selected. With setting it to Default, the datum depends on the positioning mode, e.g. WGS84 for standalone positioning.
    • Since the standardized GGA message does only provide the orthometric height (= MSL height = distance from Earth's surface to geoid) and the geoid undulation (distance from geoid to ellipsoid) for which non-WGS84 datums cannot be specified, it does not affect the GGA message.
    • default: Default

POI-ARP Offset

+ `poi_to_arp`: offsets of the main GNSS antenna reference point (ARP) with respect to the point of interest (POI = marker). Use for static receivers only.
+ The parameters `delta_e`, `delta_n` and `delta_u` are the offsets in the East, North and Up (ENU) directions respectively, expressed in meters.
+ All absolute positions reported by the receiver are POI positions, obtained by subtracting this offset from the ARP. The purpose is to take into account the fact that the antenna may not be located directly on the surveying POI.
+ default: `0.0`, `0.0` and `0.0`

Antenna Attitude Offset

+ `att_offset`: Angular offset between two antennas (Main and Aux) and vehicle frame
+ `heading`: The perpendicular (azimuth) axis can be compensated for by adjusting the `heading` parameter
+ `pitch`: Vertical (elevation) offset can be compensated for by adjusting the `pitch` parameter
+ default: `0.0`, `0.0` (degrees)

Antenna Specs

  • ant_type: type of your main GNSS antenna
    • For best positional accuracy, it is recommended to select a type from the list returned by the command lstAntennaInfo, Overview. This is the list of antennas for which the receiver can compensate for phase center variation.
    • By default and if ant_type does not match any entry in the list returned by lstAntennaInfo, Overview, the receiver will assume that the phase center variation is zero at all elevations and frequency bands, and the position will not be as accurate.
    • default: Unknown
  • ant_serial_nr: serial number of your main GNSS antenna
  • ant_aux1_type and ant_aux1_serial_nr: same for Aux1 antenna

Leap Seconds

  • leap_seconds: Leap seconds are automatically gathered from the receiver via the SBF block ReceiverTime. If a log file is used for simulation and this block was not recorded, the number of leap seconds that have been inserted up until the point of ROSaic usage can be set by this parameter.
    • At the time of writing the code (2020), the GPS time, which is unaffected by leap seconds, was ahead of UTC time by 18 leap seconds. Adapt the leap_seconds parameter accordingly as soon as the next leap second is inserted into the UTC time or in case you are using ROSaic for the purpose of simulations.

Polling Periods

  • polling_period.pvt: desired period in milliseconds between the polling of two consecutive PVTGeodetic, PosCovGeodetic, PVTCartesian and PosCovCartesian blocks and - if published - between the publishing of two of the corresponding ROS messages (e.g. septentrio_gnss_driver/PVTGeodetic.msg). Consult firmware manual for allowed periods. If the period is set to a lower value than the receiver is capable of, it will be published with the next higher period. If set to 0, the SBF blocks are output at their natural renewal rate (OnChange).
  • polling_period.rest: desired period in milliseconds between the polling of all other SBF blocks and NMEA sentences not addressed by the previous parameter, and - if published - between the publishing of all other ROS messages
    • default: 500 (2 Hz)

Time Systems

  • use_gnss_time: true if the ROS message headers' unix epoch time field shall be constructed from the TOW/WNC (in the SBF case) and UTC (in the NMEA case) data, false if those times shall be taken by the driver from ROS time. If use_gnss_time is set to true, make sure the ROS system is synchronized to an NTP time server either via internet or ideally via the Septentrio receiver since the latter serves as a Stratum 1 time server not dependent on an internet connection. The NTP server of the receiver is automatically activated on the Septentrio receiver (for INS/GNSS a firmware >= 1.3.3 is needed).
    • default: true
  • latency_compensation: Rx reports processing latency in PVT and INS blocks. If set to truethis latency is subtracted from ROS timestamps in related blocks (i.e., use_gnss_time set to false). Related blocks are INS, PVT, Covariances, and BaseVectors. In case of use_gnss_time set to true, the latency is already compensated within the RX and included in the reported timestamps.
    • default: false

RTK corrections

  • rtk_settings: determines RTK connection parameters
    • There are multiple possibilities to feed RTK corrections to the Rx. They may be set simultaneously and the Rx will choose the nearest source.
      • a) ntrip_# if the Rx has internet access and is able to receieve NTRIP streams from a caster. Up to three NTRIP connections are possible.
      • b) ip_server_# if corrections are to be receieved via TCP/IP for example over Data Link from Septentrio's RxTools is installed on a computer. Up to five IP server connections are possible.
      • c) serial_# if corrections are to be receieved via a serial port for example over radio link from a local RTK base or over Data Link from Septentrio's RxTools installed on a computer. Up to five serial connections are possible.
    • ntrip_#: for receiving corretions from an NTRIP caster (# is from 1 ... 3).
      • id: NTRIP connection NTR1, NTR2, or NTR3.
      • default: ""
      • caster: is the hostname or IP address of the NTRIP caster to connect to.
      • default: ""
      • caster_port: IP port of the NTRIP caster.
      • default: 2021
      • username: user name for the NTRIP caster.
      • default: ""
      • pasword: password for the NTRIP caster. The receiver encrypts the password so that it cannot be read back with the command "getNtripSettings".
      • default: ""
      • mountpoint: mount point of the NTRP caster to be used.
      • default: ""
      • version: argument specifies which version of the NTRIP protocol to use (v1 or v2).
      • default: "v2"
      • tls: determines wether to use TLS.
      • default: false
      • fingerprint: fingerprint to be used if the certificate is self-signed. If the caster’s certificate is known by a publicly-trusted certification authority, fingerprint should be left empty.
      • default: ""
      • rtk_standard: determines the RTK standard, options are auto, RTCMv2, RTCMv3, or CMRv2.
      • default: "auto"
      • send_gga: specifies whether or not to send NMEA GGA messages to the NTRIP caster, and at which rate. It must be one of auto, off, sec1, sec5, sec10 or sec60. In auto mode, the receiver automatically sends GGA messages if requested by the caster.
      • default: "auto"
      • keep_open: determines wether this connection shall be kept open. If set to true the Rx will still be able to receive RTK corrections to improve precision after driver is shut down.
      • default: true
    • ip_server_#: for receiving corretions via TCP/IP (# is from 1 ... 5).
      • id: specifies the IP server IPS1, IPS2, IPS3, IPS4, or IPS5. Note that ROSaic will send GGA messages on this connection if send_gga is set, such that in the Data Link application of RxTools one just needs to set up a TCP client to the host name as found in the ROSaic parameter device with the port as found in port. If the latter connection were connection 1 on Data Link, then connection 2 would set up an NTRIP client connecting to the NTRIP caster as specified in the above parameters in order to forward the corrections from connection 2 to connection 1.
      • default: ""
      • port: its port number of the connection that ROSaic establishes on the receiver. When selecting a port number, make sure to avoid conflicts with other services.
      • default: 0
      • rtk_standard: determines the RTK standard, options are auto, RTCMv2, RTCMv3, or CMRv2.
      • default: ""
      • send_gga: specifies whether or not to send NMEA GGA messages to the NTRIP caster, and at which rate. It must be one of auto, off, sec1, sec5, sec10 or sec60. In auto mode, the receiver sends with sec1.
      • default: "auto"
      • keep_open: determines wether this connection shall be kept open. If set to true the Rx will still be able to receive RTK corrections to improve precision after driver is shut down.
      • default: true
    • serial_#: for receiving corretions via serial connection (# is from 1 ... 5).
      • port: Serial connection COM1, COM2, COM3, USB1, or USB2 on which corrections could be forwarded to the Rx from a serially connected radio link modem or via Data Link for example.
      • default: ""
      • baud_rate: sets the baud rate of this port for genuine serial ports, i.e., not relevant for USB connection.
      • default: 115200
      • rtk_standard: determines the RTK standard, options are auto, RTCMv2, RTCMv3, or CMRv2.
      • default: "auto"
      • send_gga: specifies whether or not to send NMEA GGA messages to the NTRIP caster, and at which rate. It must be one of auto, off, sec1, sec5, sec10 or sec60. In auto mode, the receiver sends with sec1.
      • default: "auto"
      • keep_open: determines wether this connection shall be kept open. If set to true the Rx will still be able to receive RTK corrections to improve precision after driver is shut down.
      • default: true

INS Specs

+ `ins_spatial_config`: Spatial configuration of INS/IMU. Coordinates according to vehicle related frame directions chosen by `use_ros_axis_orientation` (front-left-up if `true` and front-right-down if `false`).
  + `imu_orientation`: IMU sensor orientation
    + Parameters `theta_x`, `theta_y` and `theta_z` are used to determine the sensor orientation with respect to the vehicle frame. Positive angles correspond to a right-handed (clockwise) rotation of the IMU with respect to its nominal orientation (see below). The order of the rotations is as follows: `theta_z` first, then `theta_y`, then `theta_x`.
    + The nominal orientation is where the IMU is upside down and with the `X axis` marked on the receiver pointing to the front of the vehicle. By contrast, for `use_ros_axis_orientation: true`, nominal orientation is where the `Z axis` of the IMU is pointing upwards and also with the `X axis` marked on the receiver pointing to the front of the vehicle.
    + default: `0.0`, `0.0`, `0.0` (degrees)
  + `poi_lever_arm`: The lever arm from the IMU reference point to a user-defined POI
    + Parameters `delta_x`,`delta_y` and `delta_z` refer to the vehicle reference frame
    + default: `0.0`, `0.0`, `0.0` (meters)
  + `ant_lever_arm`: The lever arm from the IMU reference point to the main GNSS antenna
    + The parameters `x`,`y` and `z` refer to the vehicle reference frame
    + default: `0.0`, `0.0`, `0.0` (meters)
  + `vsm_lever_arm`: The lever arm from the IMU reference point to the velocity sensor
    + The parameters `vsm_x`,`vsm_y` and `vsm_z` refer to the vehicle reference frame 
    + default: `0.0`, `0.0`, `0.0` (meters)
+ `ins_initial_heading`: How the receiver obtains the initial INS/GNSS integrated heading during the alignment phase
    + In case it is `auto`, the initial integrated heading is determined from GNSS measurements.
    + In case it is `stored`, the last known heading when the vehicle stopped before switching off the receiver is used as initial heading. Use if vehicle does not move when the receiver is switched off.
    + default: `auto`
+ `ins_std_dev_mask`: Maximum accepted error
  + `att_std_dev`: Configures an output limit on standard deviation of the attitude angles (max error accepted: 5 degrees)
  + `pos_std_dev`: Configures an output limit on standard deviation of the position (max error accepted: 100 meters)
  + default: `5` degrees, `10` meters    
+ `ins_use_poi`: Whether or not to use the POI defined in `ins_spatial_config.poi_lever_arm`
  + If true, the point at which the INS navigation solution (e.g. in `insnavgeod` ROS topic) is calculated will be the POI as defined above (`poi_frame_id`), otherwise it'll be the main GNSS antenna (`frame_id`). Has to be set to `true` if tf shall be published.
  + default: `true`
+ `ins_vsm`: Configuration of the velocity sensor measurements.
  + `ros`: VSM info received from ROS msgs
    + `source`: Specifies which ROS message type shall be used, options are `odometry` or `twist`. Accordingly, a subscriber is established of the type [`nav_msgs/Odometry.msg`](https://docs.ros2.org/foxy/api/nav_msgs/msg/Odometry.html) or [`geometry_msgs/TwistWithCovarianceStamped.msg`](https://docs.ros2.org/foxy/api/geometry_msgs/msg/TwistWithCovarianceStamped.html) listening on the topics `odometry_vsm` or `twist_vsm` respectively. Only linear velocities are evaluated. Measurements have to be with respect to the frame aligned with the vehicle and defined by `ins_spatial_config.vsm_lever_arm` or tf-frame `vsm_frame_id`, see also comment in [`nav_msgs/Odometry.msg`](https://docs.ros2.org/foxy/api/nav_msgs/msg/Odometry.html) that twist should be specified in `child_frame_id`.
      + default: ""
    + `config`: Defines which measurements belonging to the respective axes are forwarded to the INS. In addition, non-holonomic constraints may be introduced for directions known to be restricted in movement. For example, a vehicle with Ackermann steering is limited in its sidewards and upwards movement. So, even if only motion in x-direction may be measured, zero-velocities for y and z may be sent. Only has to be set if `ins_vsm.ros.source`is set to `odometry` or `twist`.
      + default: []
    + `variances_by_parameter`: Wether variances shall be entered by parameter `ins_vsm.ros.variances` or the values from inside the ROS messages are used. Only has to be set if `ins_vsm.source`is set to `odometry` or `twist`.
      + default: false
    + `variances`: Variances of the respective axes. Only have to be set if `ins_vsm.variances_by_parameter` is set to `true`. Values must be > 0.0, else measurements cannot not be used.
      + default: []
  + `ip_server`:
    + `id`: IP server to receive the VSM info (e.g. `IPS2`).
        + default: ""
    + `port`: TCP port to receive the VSM info. When selecting a port number, make sure to avoid conflicts with other services.
      + default: 0
    + `keep_open` determines wether this connections to receive VSM shall be kept open on driver shutdown. If set to `true` the Rx will still be able to use external VSM info to improve its localization.
      + default: `true`
  + `serial`:
    + `port`: Serial port to receive the VSM info.
      + default: ""
    + `baud_rate`: Baud rate of the serial port to receive the VSM info.
      + default: 115200
    + `keep_open` determines wether this connections to receive VSM shall be kept open on driver shutdown. If set to `true` the Rx will still be able to use external VSM info to improve its localization.
      + default: `true`

Logger

+ `activate_debug_log`: `true` if ROS logger level shall be set to debug.

  • Parameters Configuring (Non-)Publishing of ROS Messages

    NMEA/SBF Messages to be Published

    • publish.gpgga: true to publish nmea_msgs/GPGGA.msg messages into the topic /gpgga
    • publish.gprmc: true to publish nmea_msgs/GPRMC.msg messages into the topic /gprmc
    • publish.gpgsa: true to publish nmea_msgs/GPGSA.msg messages into the topic /gpgsa
    • publish.gpgsv: true to publish nmea_msgs/GPGSV.msg messages into the topic /gpgsv
    • publish.measepoch: true to publish septentrio_gnss_driver/MeasEpoch.msg messages into the topic /measepoch
    • publish.galauthstatus: true to publish septentrio_gnss_driver/GALAuthStatus.msg messages into the topic /galauthstatus and corresponding /diganostics
    • publish.aimplusstatus: true to publish septentrio_gnss_driver/RFStatus.msg messages into the topic /rfstatus, septentrio_gnss_driver/AIMPlusStatus.msg messages into /aimplusstatus and corresponding /diganostics. Some information is only available with active OSNMA.
    • publish.pvtcartesian: true to publish septentrio_gnss_driver/PVTCartesian.msg messages into the topic /pvtcartesian
    • publish.pvtgeodetic: true to publish septentrio_gnss_driver/PVTGeodetic.msg messages into the topic /pvtgeodetic
    • publish.basevectorcart: true to publish septentrio_gnss_driver/BaseVectorCart.msg messages into the topic /basevectorcart
    • publish.basevectorgeod: true to publish septentrio_gnss_driver/BaseVectorGeod.msg messages into the topic /basevectorgeod
    • publish.poscovcartesian: true to publish septentrio_gnss_driver/PosCovCartesian.msg messages into the topic /poscovcartesian
    • publish.poscovgeodetic: true to publish septentrio_gnss_driver/PosCovGeodetic.msg messages into the topic /poscovgeodetic
    • publish.velcovcartesian: true to publish septentrio_gnss_driver/VelCovCartesian.msg messages into the topic /velcovcartesian
    • publish.velcovgeodetic: true to publish septentrio_gnss_driver/VelCovGeodetic.msg messages into the topic /velcovgeodetic
    • publish.atteuler: true to publish septentrio_gnss_driver/AttEuler.msg messages into the topic /atteuler
    • publish.attcoveuler: true to publish septentrio_gnss_driver/AttCovEuler.msg messages into the topic /attcoveuler
    • publish.gpst: true to publish sensor_msgs/TimeReference.msg messages into the topic /gpst
    • publish.navsatfix: true to publish sensor_msgs/NavSatFix.msg messages into the topic /navsatfix
    • publish.gpsfix: true to publish gps_msgs/GPSFix.msg messages into the topic /gpsfix
    • publish.pose: true to publish geometry_msgs/PoseWithCovarianceStamped.msg messages into the topic /pose
    • publish.twist: true to publish geometry_msgs/TwistWithCovarianceStamped.msg messages into the topics /twist and /twist_ins respectively
    • publish.diagnostics: true to publish diagnostic_msgs/DiagnosticArray.msg messages into the topic /diagnostics
    • publish.insnavcart: true to publish septentrio_gnss_driver/INSNavCart.msg message into the topic/insnavcart
    • publish.insnavgeod: true to publish septentrio_gnss_driver/INSNavGeod.msg message into the topic/insnavgeod
    • publish.extsensormeas: true to publish septentrio_gnss_driver/ExtSensorMeas.msg message into the topic/extsensormeas
    • publish.imusetup: true to publish septentrio_gnss_driver/IMUSetup.msg message into the topic/imusetup
    • publish.velsensorsetup: true to publish septentrio_gnss_driver/VelSensorSetup.msgs message into the topic/velsensorsetup
    • publish.exteventinsnavcart: true to publish septentrio_gnss_driver/ExtEventINSNavCart.msgs message into the topic/exteventinsnavcart
    • publish.exteventinsnavgeod: true to publish septentrio_gnss_driver/ExtEventINSNavGeod.msgs message into the topic/exteventinsnavgeod
    • publish.imu: true to publish sensor_msgs/Imu.msg message into the topic/imu
    • publish.localization: true to publish nav_msgs/Odometry.msg message into the topic/localization
    • publish.tf: true to broadcast tf of localization. ins_use_poi must also be set to true to publish tf. Note that only one of publish.tf or publish.tf_ecef may be true.
    • publish.localization_ecef: true to publish nav_msgs/Odometry.msg message into the topic/localization related to ECEF frame.
    • publish.tf_ecef: true to broadcast tf of localization related to ECEF frame. ins_use_poi must also be set to true to publish tf. Note that only one of publish.tf or publish.tf_ecef may be true.

ROS Topic Publications

A selection of NMEA sentences, the majority being standardized sentences, and proprietary SBF blocks is translated into ROS messages, partly generic and partly custom, and can be published at the discretion of the user into the following ROS topics. All published ROS messages, even custom ones, start with a ROS generic header std_msgs/Header.msg, which includes the receiver time stamp as well as the frame ID, the latter being specified in the ROS parameter frame_id.

Available ROS Topics

  • /gpgga: publishes nmea_msgs/Gpgga.msg - converted from the NMEA sentence GGA.
  • /gprmc: publishes nmea_msgs/Gprmc.msg - converted from the NMEA sentence RMC.
  • /gpgsa: publishes nmea_msgs/Gpgsa.msg - converted from the NMEA sentence GSA.
  • /gpgsv: publishes nmea_msgs/Gpgsv.msg - converted from the NMEA sentence GSV.
  • /measepoch: publishes custom ROS message septentrio_gnss_driver/MeasEpoch.msg, corresponding to the SBF block MeasEpoch.
  • /galauthstatus: publishes custom ROS message septentrio_gnss_driver/GALAuthStatus.msg, corresponding to the SBF block GALAuthStatus.
  • /rfstatus: publishes custom ROS message septentrio_gnss_driver/RFStatus.msg, compiled from the SBF block RFStatus.
  • /aimplusstatus: publishes custom ROS message septentrio_gnss_driver/AIMPlusStatus.msg, reporting status of AIM+. Converted from SBF blocks RFStatus and optionally GALAuthStatus. For the latter OSNMA has to be activated.
  • /pvtcartesian: publishes custom ROS message septentrio_gnss_driver/PVTCartesian.msg, corresponding to the SBF block PVTCartesian (GNSS case) or INSNavGeod (INS case).
  • /pvtgeodetic: publishes custom ROS message septentrio_gnss_driver/PVTGeodetic.msg, corresponding to the SBF block PVTGeodetic (GNSS case) or INSNavGeod (INS case).
  • /basevectorcart: publishes custom ROS message septentrio_gnss_driver/BaseVectorCart.msg, corresponding to the SBF block BaseVectorCart.
  • /basevectorgeod: publishes custom ROS message septentrio_gnss_driver/BaseVectorGeod.msg, corresponding to the SBF block BaseVectorGeod.
  • /poscovcartesian: publishes custom ROS message septentrio_gnss_driver/PosCovCartesian.msg, corresponding to SBF block PosCovCartesian (GNSS case) or INSNavGeod (INS case).
  • /poscovgeodetic: publishes custom ROS message septentrio_gnss_driver/PosCovGeodetic.msg, corresponding to SBF block PosCovGeodetic (GNSS case) or INSNavGeod (INS case).
  • /velcovcartesian: publishes custom ROS message septentrio_gnss_driver/VelCovCartesian.msg, corresponding to SBF block VelCovCartesian (GNSS case).
  • /velcovgeodetic: publishes custom ROS message septentrio_gnss_driver/VelCovGeodetic.msg, corresponding to SBF block VelCovGeodetic (GNSS case).
  • /atteuler: publishes custom ROS message septentrio_gnss_driver/AttEuler.msg, corresponding to SBF block AttEuler.
  • /attcoveuler: publishes custom ROS message septentrio_gnss_driver/AttCovEuler.msg, corresponding to the SBF block AttCovEuler.
  • /gpst (for GPS Time): publishes generic ROS message sensor_msgs/TimeReference.msg, converted from the PVTGeodetic (GNSS case) or INSNavGeod (INS case) block's GPS time information, stored in its block header.
  • /navsatfix: publishes generic ROS message sensor_msgs/NavSatFix.msg, converted from the SBF blocks PVTGeodetic,PosCovGeodetic (GNSS case) or INSNavGeod (INS case)
  • /gpsfix: publishes generic ROS message gps_msgs/GPSFix.msg, which is much more detailed than sensor_msgs/NavSatFix.msg, converted from the SBF blocks PVTGeodetic, PosCovGeodetic, ChannelStatus, MeasEpoch, AttEuler, AttCovEuler, VelCovGeodetic, DOP (GNSS case) or INSNavGeod, DOP (INS case). In order to publish heading information, the field dip is diverted from its intended meaning an populated with the heading angle and err_dip with its uncertainty.
  • /pose: publishes generic ROS message geometry_msgs/PoseWithCovarianceStamped.msg, converted from the SBF blocks PVTGeodetic, PosCovGeodetic, AttEuler, AttCovEuler (GNSS case) or INSNavGeod (INS case).
    • Note that GNSS provides absolute positioning, while robots are often localized within a local level cartesian frame. The pose field of this ROS message contains position with respect to the absolute ENU frame (longitude, latitude, height), i.e. not a cartesian frame, while the orientation is with respect to a vehicle-fixed (e.g. for mosaic-x5 in moving base mode via the command setAttitudeOffset, ...) !local! NED frame or ENU frame if use_ros_axis_directions is set true. Thus the orientation is !not! given with respect to the same frame as the position is given in. The cross-covariances are hence set to 0.
  • /twist: publishes generic ROS message geometry_msgs/TwistWithCovarianceStamped.msg, converted from the SBF blocks PVTGeodetic and VelCovGeodetic.
  • /twist_ins: publishes generic ROS message geometry_msgs/TwistWithCovarianceStamped.msg, converted from SBF block INSNavGeod.
  • /insnavcart: publishes custom ROS message septentrio_gnss_driver/INSNavCart.msg, corresponding to SBF block INSNavCart
  • /insnavgeod: publishes custom ROS message septentrio_gnss_driver/INSNavGeod.msg, corresponding to SBF block INSNavGeod
  • /extsensormeas: publishes custom ROS message septentrio_gnss_driver/ExtSensorMeas.msg, corresponding to SBF block ExtSensorMeas.
  • /imusetup: publishes custom ROS message septentrio_gnss_driver/IMUSetup.msg, corresponding to SBF block IMUSetup.
  • /velsensorsetup: publishes custom ROS message septentrio_gnss_driver/VelSensorSetup.msg corresponding to SBF block VelSensorSetup.
  • /exteventinsnavcart: publishes custom ROS message septentrio_gnss_driver/INSNavCart.msg, corresponding to SBF block ExtEventINSNavCart.
  • /exteventinsnavgeod: publishes custom ROS message septentrio_gnss_driver/INSNavGeod.msg, corresponding to SBF block ExtEventINSNavGeod.
  • /diagnostics: accepts generic ROS message diagnostic_msgs/DiagnosticArray.msg, converted from the SBF blocks QualityInd, ReceiverStatus and ReceiverSetup
  • /imu: accepts generic ROS message sensor_msgs/Imu.msg, converted from the SBF blocks ExtSensorMeas and INSNavGeod.
    • The ROS message sensor_msgs/Imu.msg can be fed directly into the robot_localization of the ROS navigation stack. Note that use_ros_axis_orientation should be set to true to adhere to the ENU convention.
  • /localization: accepts generic ROS message nav_msgs/Odometry.msg, converted from the SBF block INSNavGeod and transformed to UTM.
    • The ROS message nav_msgs/Odometry.msg can be fed directly into the robot_localization of the ROS navigation stack. Note that use_ros_axis_orientation should be set to true to adhere to the ENU convention.
  • /localization_ecef: accepts generic ROS message nav_msgs/Odometry.msg, converted from the SBF blocks INSNavCart and INSNavGeod.
    • The ROS message nav_msgs/Odometry.msg can be fed directly into the robot_localization of the ROS navigation stack. Note that use_ros_axis_orientation should be set to true to adhere to the ENU convention.

Suggestions for Improvements

Some Ideas + Equip ROSaic with an NTRIP client such that it can forward corrections to the receiver independently of `Data Link`.

Adding New SBF Blocks or NMEA Sentences

Steps to Follow Is there an SBF or NMEA message that is not being addressed while being important to your application? If yes, follow these steps: 1. Find the log reference of interest in the publicly accessible, official documentation. Hence select the reference guide file, e.g. for mosaic-x5 in the [product support section for mosaic-X5](https://www.septentrio.com/en/support/mosaic/mosaic-x5), Chapter 4, of Septentrio's homepage. 2. SBF: Add a new `.msg` file to the `../msg` folder. And modify the `../CMakeLists.txt` file by adding a new entry to the `add_message_files` section. 3. Add msg header and typedef to `typedefs.hpp`. 4. Parsers: - SBF: Add a parser to the `sbf_blocks.hpp` file. - NMEA: Construct two new parsing files such as `gpgga.cpp` to the `../src/septentrio_gnss_driver/parsers/nmea_parsers` folder and one such as `gpgga.hpp` to the `../include/septentrio_gnss_driver/parsers/nmea_parsers` folder. 5. Processing the message/block: - SBF: Extend the `SbfId` enumeration in the `message_handler.hpp` file with a new entry. - SBF: Extend the SBF switch-case in `message_handler.cpp` file with a new case. - NMEA: Extend the `nmeaMap_` in the `message_handler.hpp` file with a new pair. - NMEA: Extend the NMEA switch-case in `message_handler.cpp` file with a new case. 6. Create a new `publish/..` ROSaic parameter in the `../config/rover.yaml` file and create a boolean variable `publish_xxx` in the struct in the `settings.h` file. Parse the parameter in the `rosaic_node.cpp` file. 7. Add SBF block or NMEA to data stream setup in `communication_core.cpp` (function `configureRx()`).
CHANGELOG

Changelog for package septentrio_gnss_driver

1.3.2 (2022-11-19) -----------* Merge pull request #106 from thomasemter/dev/next2 Fix IMU units * Fix topics namespace * Fix units of imu angular rates * Merge pull request #96 from septentrio-gnss/dev2 Dev2 * Contributors: Thomas Emter, Tibor Dome, septentrio-users

1.3.1 (2022-07-06)

  • New Features

    : - Recovery from connection interruption - Add option to bypass configuration of Rx - Add tests - OSNMA - Latency compensation for ROS timestamps - Output of SBf block VelCovCartesian - Support for UDP and TCP via IP server - New VSM handling allows for unknown variances (INS firmware >= 1.4.1) - Add heading angle to GPSFix msg (by diverting dip field, cf. readme)

  • Improvements

    : - Rework IO core and message handling - Unified stream processing - Internal data queue - Prevent message loss in file reading - Add some explanatory warnings for parameter mismatches - Add units to message definitions

  • Fixes

    : - navsatfix for INS - Empty headers - Single antenna receiver setup

  • Preliminary Features

    : - Output of localization and tf in ECEF frame, testing and feedback welcome

  • Commits

    : - Merge pull request #83 from thomasemter/dev/next2 Update readme - Add expected release dates - Add known issues to readme - Update version - Update readme - Merge pull request #82 from thomasemter/dev/next2 Fix spelling - Categorize stream params - Add keep alive check for TCP - Fix spelling - Add TCP communication via static IP server - Add units to msgs - Fix spelling - Merge pull request #76 from thomasemter/dev/next2 upcoming release - Add heading to GPSFix msg - Move constant - Change log level of firmware check - Add improved VSM handling - Change INS in GNSS node detection to auto - Fix invald v_x var case - Refine readme on UDP - Improve server duplicate check - Add more info un UDP configuration - Fix publish check - Add more publishing checks for configured Rx - Add const for max udp packet size - Update readme and changelog - Add device check to node - Fix param name separators - Add checks for IP server duplicates - Add latency compensation to att msgs - Add device check logic - Add UDP params and setup logic - Fix multi msg per packet - Fix localization stamp and tf publishing - Change VSM to be averaged and published with 2 Hz - Change VSM to be averaged and published with 2 Hz - Always publish raw IMU data as indicated - Change to empty fields - Refine diagnostics naming scheme and add trigger to ensure emission of ReceiverSetup - Change diagnostics naming scheme - Add missing new params to gnss.yaml - Expand readme on AIM+ - Reformulate readme about ROS and ROS2 - Add custom message to report AIM+ status - Catch invalid UTM conversion - Robustify command reset - Add RFStatus diagnostics - Add VelCovCartesian output - Refine Rx type check - Add option for latency compensation - Fix param type misinterpretation - Add OSNMA msg and diagnostics - Update changelog - Refine README and fix compiled message logic - Update changelog - Add warning for configuring INS as GNSS - Add warn log for misconfiguration - Fix pose publishing rate - Fix navsatfix publishing - Make vars const - Merge rework of internal IO handling - Change connection thread - Fix attitude cov flipped twice - Add cov alignment from true north to grid north - Rename meridian convergence and fix sense - Remove obsolete define - Add tests - Rename example launch files so they are found by auto-completion - Merge branch \'dev/ros2\' into dev/next2 - Fix lat/long in rad - Fix readme concerning ROS 2 distros - Reorder localization msg filling - Update readme - Fix NED to ECEF rotation matrix - Add localization ECEF publishing - Add ecef localization msg - Add local to ecef transforms - Contributors: Thomas Emter, Tibor Dome

1.2.3 (2022-11-09)

  • New Features

    : - Twist output option - Example config files for GNSS and INS - Get leap seconds from receiver - Firmware check - VSM from odometry or twist ROS messages - Add receiver type in case INS is used in GNSS mode - Add publishing of base vector topics

  • Improvements

    : - Rework RTK corrections parameters and improve flexibility

  • Fixes

    : - /tf not being published without /localization - Twist covariance matrix of localization - Support 5 ms period for IMU explicitly

1.2.2 (2022-06-22)

  • Fixes

    : - Memory corruption under adverse conditions

  • Commits

    : - Merge pull request #66 from thomasemter/dev/next2 Fix memory corruption - Fix parameter warnings - Reset buffer size to 16384 - Update changelog - Fix memory corruption - Replace maps with unordered_maps - Overload timestamp function - Fix frame ids for INS msgs - Add define to avoid usage of deprecated header - Change readme on gps-msgs packet - Add info on user credentials - Fix spelling in readme - Merge remote-tracking branch \'upstream/ros2\' into dev/next2 - Add comment for heading from pose - Contributors: Thomas Emter, Tibor Dome

1.2.1 (2022-05-16)

  • New Features

    : - Add login credentials - Activate NTP server if use_gnss_time is set to true

  • Improvements

    : - Add NED option to localization

  • Fixes

    : - IMU orientation for ROS axis convention

  • Commits

    : - Merge pull request #63 from thomasemter/dev/next2 Small fixes and additions - Merge pull request #60 from wep21/support-rolling fix: modify build error for rolling/humble - Revert change for deprecation warning in Humble - Change links to reflect ROS2 - Amend readme regarding robot_localization - Fix compiler warnings for humble - Add more explanations for IMU orientation in ROS convention - Fix formatting in readme - Fix package name in readme - Update readme - Update changelog - Fix IMU orientation for ROS axis orientation - Activate NTP only if GNSS time is used - Add NED option to localization - Set NMEA header to GP - Update readme and changelog - Activate NTP server - Add credentials for access control - fix: modify build error for rolling/humble - Contributors: Daisuke Nishimatsu, Thomas Emter, Tibor Dome

1.2.0 (2022-04-27)

  • New Features

    : - Add option to use ROS axis orientations according to REP103 - Add frame_id parameters - Add option to get frames from tf - Publishing of cartesian localization in UTM (topic and/or tf) for INS - Publishing of IMU topic for INS - Publishing of MeasEpoch - ROS2 branch

  • Improvements

    : - Add multi antenna option - Increase number of SBF streams - Add option to set polling_period to \"on change\" - Increased buffer size from 8192 to 131072 bytes - Add endianess aware parsers - Only publish topics set to true - Add parameter to switch DEBUG logging on and off - Change GPxxx messages to ROS built-in types - Remove duplicate INS msg types

  • Fixes

    : - Setting of antenna type - Publishing rate interconnections of gpsfix and velcovgeodetic - Missing quotes for antenna type - Broken attitude parsing pose and gpsfix from INS - IMU orientation was not sent to Rx - Graceful shutdown of threads

  • Commits

    : - Merge branch \'dev\' - Prepare new release - Prepare new release - Merge pull request #53 from thomasemter/dev/refactor Very last changes - Add geographic lib dependency to package.xml - Add comment for frame of main antenna - Move utm zone locking section in readme - Reformulate readme section on frames - Merge pull request #52 from thomasemter/dev/refactor Last changes - Change frame id back to poi_frame_id - Make error log more explicit - Merge pull request #49 from thomasemter/dev/refactor Improve IMU blocks sync and do-not-use value handling - Fix buffer size in changelog - Turn off Nagle\'s algorithm for TCP - Fix changelog formatting - Fix readme - Set default base frame to base_link - Fix valid tow check logic - Increase buffer size for extreme stress tests - Fix crc check - Fix and streamline tf handling - Add checks for validity of values - Fix rad vs deg - Update changelog - Add some comments - Set stdDevMask to values > 0.0 in node - Set stdDevMask to values > 0.0 - Add info on RNDIS and set it to default - Increase default serial baud rate - Add parameter to set log level to debug - Change defaults for publishers in node - Put publish params together and fix mismatch in readme - Improve IMU blocks sync and do-not-use value handling - Merge pull request #48 from thomasemter/dev/refactor Fix measepoch not publishing without gpsfix - Fix measepoch not publishing without gpsfix - Merge pull request #47 from thomasemter/dev/refactor Dev/refactor - Publish only messages set to true - Remove leftover declaration - Merge branch \'dev/endianess_agnostic\' into dev/refactor - Update readme to reflect endianess aware parsing - Remove msg smart pointers - Fix array assertion failure - Cleanup - Add ReceiverStatus parser - Add QualityInd parser - Add DOP parser - Add ReceiverSetup parser - Fix MeasEpoch and ChannelStatus parsers, add measepoch publishing - Add ChannelStatus parser - Add MeasEpoch parser - Add IMU and VelSensor setup parsers - Add Cov SBF parsers - Add templated qi parser function - Add AttEuler+Cov parser - Revert ordering change inside INSNav ROS msgs - Add ExtSensorMeas parser - Add PVT parsers - Add range checks to parsers - Replace INSNav grammar with parsers - Test parser vs. grammar for better performance - Fix sb_list check - Add IMU and VelSensor setup grammars - Move adapt ROS header to typedefs.h - Add revision check to MeasEpoch - Fix ReceiverStatus grammar - Extend ReceiverSetup and add revision checks - Change logger and fix loop range - Remove reserved bytes from parsing - Remove obsolete structs - Directly parse Cov SBFs to ROS msg - Directly parse PVT SBFs, remove obsolete ids - Rename rev to revision - Fix block header parsing - Directly parse AttEuler to ROS msg - Directly parse to ROS msgs for INSNavXxx - Exchange pow with square function and remove casts - Merge pull request #46 from thomasemter/dev/refactor Dev/refactor - Simplify sync bytes check - Move tow/wnc to BlockHeader - Adjust order in INSNav ros msgs - Fix INSNav grammars - Change BlockHeader structure - Remove length ref from header - Rectify sb_list check of INSNavXxx - Add automtatic activation of multi-antenna mode - Merge branch \'dev/refactor\' of https://github.com/thomasemter/septentrio_gnss_driver into dev/refactor - Add automtatic activation of multi-antenna mode - Fix wrong scope of phoenix::ref variables - Fix AttEuler grammar - Add max size checks to QualityInd and ReceiverStatus - Replace locals with phoenix::ref in grammars - Add revision dependent parsing to PVTs - Change offset check to epsilon - Change offset check to epsilon - Fix parsing checks - Set has arrived to false on parsing error - Add INSNav grammars - Add abs to offset check - Add abs to offset check - Add Cov grammars - Remove superfluous typdefs of structs - Add ReceiverStatus grammar - Add QualityINd grammar - Merge pull request #45 from thomasemter/dev/refactor Dev/refactor - Add id check to header grammar - Add id check to header grammar - Add ReceiverSetup grammar - Add DOP grammar - Directly intialize vector to parse - Add MeasEpoch grammar - Remove duplicate msg types - Remove obsolete include - Add revision and length return to header grammar - Merge branch \'feature/endianess_agnostic\' into dev/endianess_agnostic - Make multi_antenna option also usable for gnss - Add typedefs plus some minor changes - Add warning concerning pitch angle if antennas are rotated - Add multi antenna option to ins and fix antenna offset decimal places trimming - Fix identation - Distinguish between gnss and ins for spatial config from tf - Merge pull request #43 from thomasemter/dev/refactor Dev/refactor - Add vehicle frame for clarity - Handle missing tf more gently - Merge branch \'dev/spatial_config_via_tf\' into dev/refactor - Update readme - Fix antenna offset from tf - Add automatic publishing of localization if tf is activated - Add automatic publishing of localization if tf is activated - Add spatial config via tf, to be tested - Fix crashes due to parsing errors (replacing uncatched throws) - Add tf broadcasting - Add comments - Add localization in UTM output - Add check to IMU msg sync - Change msg sync to allow for 200 Hz IMU msgs - Add ROS IMU msg - Fix IMU setup message attitude conversion - Fix pose from INS data - Fix IMU raw data rotation compensation - Make antenna attitude offset usable by GNSS - Add ros directions option to pose and fix covariances - Update readme - Merge branch \'feature/ros_axis_orientation\' into dev/refactor - Add nmea_msgs dependencies - Merge branch \'dev/nmea\' into dev/refactor - Update readme - Update readme - Add antenna offsets to conversions - Fix IMU orientation conversion - Change ExtSensorMead temperature to deg C - Add axis orientation info to readme - Fix IMU axis orientation - Change get int param - Update readme to reflect removal of aux antenna offset - Fix different antenna setup message for INS and remove obsolete aux1 antenna offset for GNSS - Fix ExtSensorMeas message filling - Fix ExtSensorMeas message to reflect available fields - Fix missing INS blocks - Fix missing INS blocks - WIP, introduce ros axis orientation option, to be tested - Add option to set pvt rate to OnChange - Add comment on NTP to readme - Change to nmea_msgs - Add automatic addition of needed sub messages - Comment out setting debug level - Add comments and fix spelling errors - Merge pull request #42 from thomasemter/dev/refactor Dev/refactor - Change to quaternion msg typedef - Comment out debug logging - Remove filling of seq field - Change msg definitions to be compatible with ROS2 - Update readme - Change make_shared for portability and add more typedefs - Add get param int fallback for numeric antenna serial numbers - Change Attitude to be published with pvt rate - Add log identifier - Add checks for relevant ros params - Concatenate multiple SBF blocks in streams - Move main into own file - Move get ros time to AsyncManager - Remove obsolete param comment - Move get ros params to base class - Change to nsec timestamp internally - Add publishing functionality to node base class - Move node handle ptr and functions to base class and rename - Add stamp to nmea parsing - Add logging in PcapReader - Add logging in CircularBuffer - Add missed logging - Add logging in AsyncManager - Add getTime function - Add logging in RxMessage - Add logging in CallbackHandlers - Add log function to node by polymorphism, logging in Comm_OI - Fix wait function and force use_gnss_time when reading from file - Add thread shutdown and remove spurious delete - Add typedefs for ins messages - Add typedefs for gnss messages - Add typedefs for ros messages - Refine shutdown - Fix shutdown escalating to SIGTERM - Move waiting for response in send function - Make functions private - Change crc to C++ - Fix variable name - Remove global variables from node cpp file - Move more global settings to settings struct - Move more global settings to settings struct - Move global settings to settings struct - Move more functions to Comm_IO - Move settings to struct and configuration to Comm_IO - Merge branch \'dev/change_utc_calculation\' into dev/refactor - Remove obsolete global variables - Move g_unix_time to class - Make has_arrived booleans class memebers and rx_message a persistent class - Make node handle a class member - Fix parsing of ID and rev - Finish ChannelStatusGrammar, to be tested - WIP, partially fix ChannelStatusGrammar - Add SBF length parsing utility - Insert spirit parsers - WIP, add omission of padding bytes - WIP, add more spirit parsers - Add parsing utilities for tow, wnc and ID - Move getId/Tow/Wnc to parsing utilities - Change UTC calculation to use tow and wnc - WIP, add boost spirit and endian buffers - Change UTC calculation to use tow and wnc

  • ROS2 Commits

    : - Prepare ros2 release - Merge pull request #54 from thomasemter/dev/ros2 ROS2 branch - Port driver to ros2

  • Change UTC calculation to use tow and wnc

  • Contributors: Thomas Emter, Tibor Dome, tibordome

1.0.8 (2021-10-23)

  • Added INS Support

1.0.7 (2021-05-18)

  • Clang formatting, publishing from SBF log, play-back of PCAP files

1.0.6 (2020-10-16)

  • ROSaic binary installation now available on Melodic & Noetic

1.0.5 (2020-10-15)

  • changed repo name
  • v1.0.4
  • 1.0.3
  • Merge pull request #22 from septentrio-gnss/local_tibor New changelog
  • New changelog
  • Merge pull request #21 from septentrio-gnss/local_tibor Added rosdoc.yaml file
  • Merge pull request #20 from septentrio-gnss/local_tibor Improved doxygen annotations
  • Merge pull request #19 from septentrio-gnss/local_tibor Improved doxygen annotations
  • Update README.md
  • Merge pull request #18 from septentrio-gnss/local_tibor Adopted ROS and C++ conventions, added ROS diagnostics msg,
  • Update README.md
  • Update README.md
  • Update README.md
  • Contributors: septentrio-users, tibordome

1.0.4 (2020-10-11)

  • Added rosdoc.yaml file
  • Improved doxygen annotations
  • Improved doxygen annotations
  • Adopted ROS and C++ conventions, added ROS diagnostics msg, removed ROS garbage value bug, added auto-detection of SBF arrival order for composite ROS msgs
  • Merge branch \'master\' of https://github.com/septentrio-gnss/rosaic
  • NTRIP with Datalink, circular buffer, reading connection descriptor, new messages
  • Update README.md
  • Contributors: septentrio-users, tibordome

1.0.3 (2020-09-30)

  • Add new config/rover.yaml file
  • Add config/rover.yaml to .gitignore
  • Merge pull request #17 from septentrio-gnss/local_tibor NTRIP with Datalink, circular buffer, reading connection descriptor..
  • Merge branch \'local_tibor\'
  • NTRIP with Datalink, circular buffer, reading connection descriptor, new messages
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #16 from septentrio-gnss/local_tibor NTRIP parameters added, reconnect_delay_s implemented,
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #15 from tibordome/local_tibor GPSFix completed, datum as new parameter
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #14 from tibordome/local_tibor GPSFix completed, datum as new parameter
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #13 from tibordome/local_tibor Added AttCovEuler.msg and AttEuler.msg
  • Merge pull request #12 from tibordome/local_tibor Fixed service field of NavSatStatus
  • Contributors: Tibor Dome, septentrio-users, tibordome

1.0.2 (2020-09-25)

  • NTRIP parameters added, reconnect_delay_s implemented, package.xml updated, ROSaic now detects connection descriptor automatically, mosaic serial port parameter added
  • GPSFix completed, datum as new parameter, ANT type and marker-to-arp distances as new parameters, BlockLength() method corrected, sending multiple commands to Rx corrected by means of mutex
  • Contributors: tibordome

1.0.1 (2020-09-22)

  • GPSFix completed, datum as new parameter, ANT type and marker-to-arp distances as new parameters, BlockLength() method corrected, sending multiple commands to Rx corrected by means of mutex
  • Added AttCovEuler.msg and AttEuler.msg
  • Fixed service field of NavSatStatus, fixed ROS header\'s seq field of each published ROS message, added write method for sending commands to Rx, successfully tested, added AttEuler, added AttCovEuler
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #11 from tibordome/local_tibor rosconsole_backend_interface dependency not needed
  • rosconsole_backend_interface dependency not needed
  • Merge pull request #10 from tibordome/local_tibor rosconsole_log4cxx dep not needed
  • rosconsole_log4cxx dep not needed
  • Merge pull request #9 from tibordome/local_tibor rosconsole_log4cxx dep not needed
  • rosconsole_log4cxx dep not needed
  • Merge pull request #8 from tibordome/local_tibor Local tibor
  • Update README.md
  • Merge pull request #7 from tibordome/local_tibor Ready for First Release
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #6 from tibordome/local_tibor Local tibor
  • Merge pull request #5 from tibordome/local_tibor TCP seems to work
  • Contributors: Tibor Dome, tibordome

1.0.0 (2020-09-11)

  • Ready for first release
  • Added Gpgga.msg and PosCovGeodetic.msg files
  • Ready for First Release
  • Ready for first release
  • Ready for first release
  • Ready for first release
  • TCP bug removed
  • TCP bug removed
  • TCP seems to work
  • Merge pull request #4 from tibordome/v0.2 V0.2
  • PVTCartesian and PVTGeodetic publishing works on serial
  • PVTCartesian and PVTGeodetic publishing works on serial
  • Merge pull request #3 from tibordome/v0.2 Add doxygen_out and Doxyfile 2nd trial
  • Add doxygen_out and Doxyfile 2nd trial
  • Merge pull request #2 from tibordome/v0.1 Add doxygen_out and Doxyfile
  • Add doxygen_out and Doxyfile
  • Update README.md
  • Create README.md
  • Update LICENSE
  • Merge pull request #1 from tibordome/add-license-1 Create LICENSE
  • Create LICENSE
  • Create LICENSE
  • Commit
  • Successfully tested publishing to /gpgga topic via serial
  • To make sure master branch exists
  • Contributors: Tibor Dome, tibordome

Wiki Tutorials

See ROS Wiki Tutorials for more details.

Source Tutorials

Not currently indexed.

Recent questions tagged septentrio_gnss_driver at Robotics Stack Exchange

septentrio_gnss_driver package from septentrio_gnss_driver repo

septentrio_gnss_driver

Package Summary

Tags No category tags.
Version 1.3.2
License BSD 3-Clause License
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/septentrio-gnss/septentrio_gnss_driver.git
VCS Type git
VCS Version ros2
Last Updated 2023-11-22
Dev Status MAINTAINED
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

ROSaic: C++ driver for Septentrio's mosaic receivers and beyond

Additional Links

Maintainers

  • Tibor Dome
  • Septentrio

Authors

  • Tibor Dome

ROSaic = ROS + mosaic

Overview

This repository hosts drivers for ROS (Melodic and Noetic) and ROS 2 (Foxy, Galactic, Humble, Rolling, and beyond) - written in C++ - that work with mosaic and AsteRx - two of Septentrio's cutting-edge GNSS and GNSS/INS receiver families - and beyond. The ROS 2 version is available in this branch, whereas the ROS 1 version is available in the branch master.

Main Features: - Supports Septentrio's single antenna GNSS, dual antenna GNSS and INS receivers - Supports serial, TCP/IP and USB connections, the latter being compatible with both serial (RNDIS) and TCP/IP protocols - Supports several ASCII (including key NMEA ones) messages and SBF (Septentrio Binary Format) blocks - Reports status of AIM+ (Advanced Interference Mitigation including OSNMA) anti-jamming and anti-spoofing. - Can publish nav_msgs/Odometry message for INS receivers - Can blend SBF blocks PVTGeodetic, PosCovGeodetic, ChannelStatus, MeasEpoch, AttEuler, AttCovEuler, VelCovGeodetic and DOP in order to publish gps_common/GPSFix and sensor_msgs/NavSatFix messages - Supports axis convention conversion as Septentrio follows the NED convention, whereas ROS is ENU. - Easy configuration of multiple RTK corrections simultaneously (via NTRIP, TCP/IP stream, or serial) - Can play back PCAP capture logs for testing purposes - Tested with the mosaic-X5, mosaic-H, AsteRx-m3 Pro+ and the AsteRx-SBi3 Pro receiver - Easy to add support for more log types

Please let the maintainers know of your success or failure in using the driver with other devices so we can update this page appropriately.

Dependencies

The ros2 branch for this driver functions on ROS Foxy, Galactic, Rolling, and Humble (Ubuntu 20.04 or 22.04 respectively). It is thus necessary to install the ROS version that has been designed for your Linux distro.

Additional ROS packages have to be installed for the NMEA and GPSFix messages.

sudo apt install ros-$ROS_DISTRO-nmea-msgs ros-$ROS_DISTRO-gps-msgs.

The serial and TCP/IP communication interface of the ROS driver is established by means of the Boost C++ library. In the unlikely event that the below installation instructions fail to install Boost on the fly, please install the Boost libraries via

sudo apt install libboost-all-dev.

Compatiblity with PCAP captures are incorporated through pcap libraries. Install the necessary headers via

sudo apt install libpcap-dev.

Conversions from LLA to UTM are incorporated through GeographicLib. Install the necessary headers via

sudo apt install libgeographic-dev

Usage

Binary Install The binary release is now available for Foxy and Galactic. To install the binary package, simply run `sudo apt-get install ros-$ROS_DISTRO-septentrio-gnss-driver`.
Build from Source The package has to be built from source using [`colcon`](https://docs.ros.org/en/humble/Tutorials/Beginner-Client-Libraries/Colcon-Tutorial.html): ``` source /opt/ros/${ROS_DISTRO}/setup.bash # In case you do not use the default shell of Ubuntu, you need to source another script, e.g. setup.sh. mkdir -p ~/septentrio/src # Note: Change accordingly depending on where you want your package to be installed. cd ~/septentrio/src git clone https://github.com/septentrio-gnss/septentrio_gnss_driver git checkout ros2 # Install mentioned dependencies (`sudo apt install ros-$ROS_DISTRO-nmea_msgs ros-$ROS_DISTRO-gps-msgs libboost-all-dev libpcap-dev libgeographic-dev`) colcon build --packages-up-to septentrio_gnss_driver # Be sure to call colcon build in the root folder of your workspace. Launch files are installed, so changing them on the fly in the source folder only works with installing by symlinks: add `--symlink-install` echo "source ~/septentrio/devel/setup.bash" >> ~/.bashrc # It is convenient if the ROS environment variable is automatically added to your bash session every time a new shell is launched. Again, this works for bash shells only. Also note that if you have more than one ROS distribution installed, ~/.bashrc must only source the setup.bash for the version you are currently using. source ~/.bashrc ``` Run tests ``` colcon test --packages-select septentrio_gnss_driver --event-handlers console_direct+ ```
Notes Before Usage + In your bash sessions, navigating to the ROSaic package can be achieved from anywhere with no more effort than `roscd septentrio_gnss_driver`. + The driver assumes that our anonymous access to the Rx grants us full control rights. This should be the case by default, and can otherwise be changed with the `setDefaultAccessLevel` command. If user control is in place user credentials can be given by parameters `login.user` and `login.password`. + ROSaic only works from C++17 onwards due to std::any() etc. + Note for setting hw_flow_control: This is a string parameter, setting it to off without quotes leads to the fact that it is not read in correctly. + Note for setting ant_(aux1)_serial_nr: This is a string parameter, numeric only serial numbers should be put in quotes. If this is not done a warning will be issued and the driver tries to parse it as integer. + Once the colcon build or binary installation is finished, adapt the `config/rover.yaml` file according to your needs or assemble a new one. Launch as composition with `ros2 launch septentrio_gnss_driver rover.launch.py` to use `rover.yaml` or add `file_name:=xxx.yaml` to use a custom config. Alternatively launch as node with `ros2 launch septentrio_gnss_driver rover_node.launch.py` to use `rover_node.yaml` or add `file_name:=xxx.yaml` to use a custom config. Specify the communication parameters, the ROS messages to be published, the frequency at which the latter should happen etc. + Besides the aforementioned config file `rover.yaml` containing all parameters, specialized launch files for GNSS `config/gnss.yaml` and INS `config/ins.yaml` respectively contain only the relevant parameters in each case. - NOTE: Unless `configure_rx` is set to `false`, this driver will overwrite the previous values of the parameters, even if the value is left to zero in the "yaml" file. + The driver was developed and tested with firmware versions >= 4.10.0 for GNSS and >= 1.3.2 for INS. Receivers with older firmware versions are supported but some features may not be available. Known limitations are: * GNSS with firmware < 4.10.0 does not support IP over USB. * GNSS with firmware < 4.12.1 does not support OSNMA. * INS with firmware < 1.3.2 does not support NTP. * INS with firmware < 1.4 does not support OSNMA. * INS with firmware < 1.4.1 does not support improved VSM handling allowing for unknown variances. * INS with firmware 1.2.0 does not support velocity aiding. * INS with firmware 1.2.0 does not support setting of initial heading. + Known issues: * UDP over USB: Blocks are sent twice on GNSS with firmware <= 4.12.1 and INS with firmware <= 1.4. For GNSS it is fixed in version 4.14 (released on June 15th 2023), for INS it will be fixed in to-be-released 1.4.1 (expected in November 2023). + If `use_ros_axis_orientation` to `true` axis orientations are converted by the driver between NED (Septentrio: yaw = 0 is north, positive clockwise) and ENU (ROS: yaw = 0 is east, positive counterclockwise). There is no conversion when setting this parameter to `false` and the angles will be consistent with the web GUI in this case. :
``` # Example configuration Settings for the Rover Rx device: tcp://192.168.3.1:28784 serial: baudrate: 921600 hw_flow_control: "off" tcp: ip_server: "" port: 0 udp: ip_server: "" port: 0 unicast_ip: "" configure_rx: true login: user: "" password: "" osnma: mode: "off" ntp_server: "" keep_open: true frame_id: gnss imu_frame_id: imu poi_frame_id: base_link vsm_frame_id: vsm aux1_frame_id: aux1 vehicle_frame_id: base_link insert_local_frame: false local_frame_id: odom get_spatial_config_from_tf: true lock_utm_zone: true use_ros_axis_orientation: true receiver_type: gnss datum: Default poi_to_arp: delta_e: 0.0 delta_n: 0.0 delta_u: 0.0 att_offset: heading: 0.0 pitch: 0.0 ant_type: Unknown ant_aux1_type: Unknown ant_serial_nr: Unknown ant_aux1_serial_nr: Unknown leap_seconds: 18 polling_period: pvt: 500 rest: 500 use_gnss_time: false latency_compensation: false rtk_settings: ntrip_1: id: "NTR1" caster: "1.2.3.4" caster_port: 2101 username: "Asterix" password: "password" mountpoint: "mtpt1" version: "v2" tls: true fingerprint: "AA:BB:56:78:90:12: ... 78:90:12:34" rtk_standard: "RTCMv3" send_gga: "auto" keep_open: true ntrip_2: id: "NTR3" caster: "5.6.7.8" caster_port: 2101 username: "Obelix" password: "password" mountpoint: "mtpt2" version: "v2" tls: false fingerprint: "" rtk_standard: "RTCMv2" send_gga: "auto" keep_open: true ip_server_1: id: "IPS3" port: 28785 rtk_standard: "RTCMv2" send_gga: "auto" keep_open: true ip_server_2: id: "IPS5" port: 28786 rtk_standard: "CMRv2" send_gga: "auto" keep_open: true serial_1: port: "COM1" baud_rate: 230400 rtk_standard: "auto" send_gga: "sec1" keep_open: true serial_2: port: "COM2" baud_rate: 230400 rtk_standard: "auto" send_gga: "off" keep_open: true publish: # For both GNSS and INS Rxs navsatfix: false gpsfix: true gpgga: false gprmc: false gpst: false measepoch: false pvtcartesian: false pvtgeodetic: true basevectorcart: false basevectorgeod: false poscovcartesian: false poscovgeodetic: true velcovcartesian: false velcovgeodetic: false atteuler: true attcoveuler: true pose: false twist: false diagnostics: false aimplusstatus: true galauthstatus: false # For GNSS Rx only gpgsa: false gpgsv: false # For INS Rx only insnavcart: false insnavgeod: false extsensormeas: false imusetup: false velsensorsetup: false exteventinsnavcart: false exteventinsnavgeod: false imu: false localization: false tf: false localization_ecef: false tf_ecef: false # INS-Specific Parameters ins_spatial_config: imu_orientation: theta_x: 0.0 theta_y: 0.0 theta_z: 0.0 poi_lever_arm: delta_x: 0.0 delta_y: 0.0 delta_z: 0.0 ant_lever_arm: x: 0.0 y: 0.0 z: 0.0 vsm_lever_arm: vsm_x: 0.0 vsm_y: 0.0 vsm_z: 0.0 ins_initial_heading: auto ins_std_dev_mask: att_std_dev: 5.0 pos_std_dev: 10.0 ins_use_poi: true ins_vsm: source: "twist" config: [true, false, false] variances_by_parameter: true variances: [0.1, 0.0, 0.0] ip_server: id: "IPS2" port: 28787 keep_open: true serial: port: "COM3" baud_rate: 115200 keep_open: true # Logger activate_debug_log: false ``` In order to launch ROSaic, one must specify all `arg` fields of the `rover.py` file which have no associated default values, i.e. for now only the `file_name` field. Hence, the launch command reads `ros2 launch septentrio_gnss_driver rover.py file_name:=rover.yaml`. If multiple port are utilized for RTK corrections and/or VSM, which shall be closed after driver shutdown (`keep_open: false`), make sure to give the driver enough time to gracefully shutdown as closing the ports takes a few seconds. This can be accomplished in the launch files by increasing the timeout of SIGTERM (e.g. `sigterm_timeout = '10',`), see example launch files`rover.py`and `rover_node.py` respectively.

Inertial Navigation System (INS): Basics

  • An Inertial Navigation System (INS) is a device which takes the rotation and acceleration solutions as obtained from its Inertial Measurement Unit (IMU) and combines those with position and velocity information from the GNSS module. Compared to a GNSS system with 7D or 8D (dual-antenna systems) phase space solutions, the combined, Kalman-filtered 9D phase space solution (3 for position, 3 for velocity, 3 for orientation) of an INS is more accurate, more precise and more stable against GNSS outages.
  • The IMU is typically made up of a 3-axis accelerometer, a 3-axis gyroscope and sometimes a 3-axis magnetometer and measures the system's angular rate and acceleration.

    Measure and Compensate for IMU-Antenna Lever Arm

    • The IMU-antenna lever-arm is the relative position between the IMU reference point and the GNSS Antenna Reference Point (ARP), measured in the vehicle frame.
    • In case of AsteRx SBi3, the IMU reference point is clearly marked on the top panel of the receiver. It is important to compensate for the effect of the lever arm, otherwise the receiver may not be able to calculate an accurate INS position.
    • The IMU/antenna position can be changed by specifying the lever arm's x,yand z parameters in the config.yaml file under the ins_spatial_config.ant_lever_arm parameter.

    Screenshot from 2021-08-03 09-23-19 (1)

    Compensate for IMU Orientation + It is important to take into consideration the mounting direction of the IMU in the body frame of the vehicle. For e.g. when the receiver is installed horizontally with the front panel facing the direction of travel, we must compensate for the IMU’s orientation to make sure the IMU reference frame is aligned with the vehicle reference frame. The IMU position and orientation is printed on the top panel, cf. image below. + The IMU's orientation can be changed by specifying the orientation angles theta_x,theta_yand theta_z in the config.yaml file under ins_spatial_config.imu_orientation + The below image illustrates the orientation of the IMU reference frame with the associated IMU orientation for the depicted installation. Note that for use_ros_axis_orientation: true sensor_default is the top left position.

    Capture (1)

  • These Steps should be followed to configure the receiver in INS integration mode:

    • Specify receiver_type: INS
    • Specify the orientation of the IMU sensor with respect to your vehicle, using the ins_spatial_config.imu_orientation parameter.
    • Specify the IMU-antenna lever arm in the vehicle reference frame. This is the vector starting from the IMU reference point to the ARP of the main GNSS antenna. This can be done by means of the ins_spatial_config.ant_lever_arm parameter.
    • Specify ins_spatial_config.vsm_lever_arm if measurements of a velocity sensor is available.
    • Alternatively the lever arms may be specified via tf. Set get_spatial_config_from_tfto true in this case.
    • If the point of interest is neither the IMU nor the ARP of the main GNSS antenna, the vector between the IMU and the point of interest can be provided with the ins_solution/poi_lever_arm parameter.
  • For further more information about Septentrio receivers, visit Septentrio support resources or check out the user manual and reference guide of the AsteRx SBi3 receiver.

ROSaic Parameters

The following is a list of ROSaic parameters found in the config/rover.yaml file. * Parameters Configuring Communication Ports and Processing of GNSS and INS Data

Connectivity Specs

  • device: location of main device connection. This interface will be used for setup communication and VSM data for INS. Incoming data streams of SBF blocks and NMEA sentences are recevied either via this interface or a static IP server for TCP and/or UDP. The former will be utilized if section stream_device.tcp and stream_device.udp are not configured.
    • serial:xxx format for serial connections,where xxx is the device node, e.g. serial:/dev/ttyS0. If using serial over USB, it is recommended to specify the port by ID as the Rx may get a different ttyXXX on reconnection, e.g. serial:/dev/serial/by-id/usb-Septentrio_Septentrio_USB_Device_xyz.
    • file_name:path/to/file.sbf format for publishing from an SBF log
    • file_name:path/to/file.pcap format for publishing from PCAP capture.
      • Regarding the file path, ROS_HOME=`pwd` in front of roslaunch septentrio... might be useful to specify that the node should be started using the executable's directory as its working-directory.
    • tcp://host:port format for TCP/IP connections
      • 28784 should be used as the default (command) port for TCP/IP connections. If another port is specified, the receiver needs to be (re-)configured via the Web Interface before ROSaic can be used.
      • An RNDIS IP interface is provided via USB, assigning the address 192.168.3.1 to the receiver. This should work on most modern Linux distributions. To verify successful connection, open a web browser to access the web interface of the receiver using the IP address 192.168.3.1.
    • default: tcp://192.168.3.1:28784
  • serial: specifications for serial communication
    • baudrate: serial baud rate to be used in a serial connection. Ensure the provided rate is sufficient for the chosen SBF blocks. For example, activating MeasEpoch (also necessary for /gpsfix) may require up to almost 400 kBit/s.
    • rx_serial_port: determines to which (virtual) serial port of the Rx we want to get connected to, e.g. USB1 or COM1
    • hw_flow_control: specifies whether the serial (the Rx's COM ports, not USB1 or USB2) connection to the Rx should have UART hardware flow control enabled or not
      • off to disable UART hardware flow control, RTS|CTS to enable it
    • default: 921600, USB1, off
  • stream_device: If left unconfigured, by default device is utilized for the data streams. Within stream_device static IP servers may be defined instead. In config mode (configure_rx set to true), TCP will be prioritized over UDP. If Rx is pre-configured, both may be set simultaneously.
    • tcp: specifications for static TCP server of SBF blocks and NMEA sentences.
      • ip_server: IP server of Rx to be used, e.g. “IPS1”.
      • port: UDP destination port.
    • udp: specifications for low latency UDP reception of SBF blocks and NMEA sentences.
      • ip_server: IP server of Rx to be used, e.g. “IPS1”.
      • port: UDP destination port.
      • unicast_ip: Set to computer's IP to use unicast (optional). If not set multicast will be used.
  • login: credentials for user authentication to perform actions not allowed to anonymous users. Leave empty for anonymous access.
    • user: user name
    • password: password

OSNMA

  • osnma: Configuration of the Open Service Navigation Message Authentication (OSNMA) feature.
    • mode: Three operating modes are supported: off where OSNMA authentication is disabled, loose where satellites are included in the PVT if they are successfully authenticated or if their authentication status is unknown, and strict where only successfully-authenticated satellites are included in the PVT. In case of strict synchronization via NTP is mandatory.
      • default: off
    • ntp_server: In strict mode, OSNMA authentication requires the availability of external time information. In loose mode, this is optional but recommended for enhanced security. The receiver can connect to an NTP time server for this purpose. Options are default to let the receiver choose an NTP server or specify one like pool.ntp.org for example.
      • default: ""
    • keep_open: Wether OSNMA shall be kept active on driver shutdown.
      • default: true

Receiver Configuration

+ configure_rx: Wether to configure the Rx according to the config file. If set to `false`, the Rx has to be configured via the web interface and the settings must be saved. On the driver side communication has to set accordingly to serial, TCP or UDP (TCP and UDP may even be used simultaneously in this case). For TCP communication it is recommended to use a static TCP server (`stream_device.tcp.ip_server` and `stream_device.tcp.port`), since dynamic connections (`device` is tcp) are not guaranteed to have the same id on reconnection. It should also be ensured that obligatory SBF blocks are activated (as of now: ReceiverTime if `use_gnss_time` is set to `true`; `PVTGeodetic`or `PVTCartesian` if latency compensation for PVT related blocks shall be used). Further, if ROS messages compiled from multiple SBF blocks, it should be ensured that all necessary blocks are activated with matching periods, details can be found in section [ROS Topic Publications](#ros-topic-publications). The messages that shall be published still have to be set to `true` in the *NMEA/SBF Messages to be Published* section. Also, parameters concerning the connection and node setup are still relevant (sections: *Connectivity Specs*, *receiver type*, *Frame IDs*, *UTM Zone Locking*, *Time Systems*, *Logger*).
  + default: true

Receiver Type

  • receiver_type: This parameter is to select the type of the Septentrio receiver
    • gnss for GNSS receivers.
    • ins for INS receivers.
    • default: gnss
  • multi_antenna: Whether or not the Rx has multiple antennas.
    • default: false

Frame IDs

  • frame_id: name of the ROS tf frame for the Rx, placed in the header of published GNSS messages. It corresponds to the frame of the main antenna.
    • In ROS, the tf package lets you keep track of multiple coordinate frames over time. The frame ID will be resolved by tf_prefix if defined. If a ROS message has a header (all of those we publish do), the frame ID can be found via rostopic echo /topic, where /topic is the topic into which the message is being published.
    • default: gnss
  • imu_frame_id: name of the ROS tf frame for the IMU, placed in the header of published IMU message
    • default: imu
  • poi_frame_id: name of the ROS tf frame for the POI, placed in the child frame_id of localization if ins_use_poi is set to true.
    • default: base_link
  • vsm_frame_id: name of the ROS tf frame for the velocity sensor.
    • default: vsm
  • aux1_frame_id: name of the ROS tf frame for the aux1 antenna.
    • default: aux1
  • vehicle_frame_id: name of the ROS tf frame for the vehicle. Default is the same as poi_frame_id but may be set otherwise.
    • default: base_link
  • local_frame_id: name of the ROS tf frame for the local frame.
    • default: odom
  • insert_local_frame: Wether to insert a local frame to published tf according to ROS REP 105. The transform from the local frame specified by local_frame_id to the vehicle frame specified by vehicle_frame_id has to be provided, e.g. by odometry. Insertion of the local frame means the transform between local frame and global frame is published instead of transform between vehicle frame and global frame.
    • default: false
  • get_spatial_config_from_tf: wether to get the spatial config via tf with the above mentioned frame ids. This will override spatial settings of the config file. For receiver type ins with multi_antenna set to true all frames have to be provided, with multi_antenna set to false, aux1_frame_id is not necessary. For type gnss with dual-antenna setup only frame_id, aux1_frame_id, and poi_frame_id are needed. For single-antenna gnss no frames are needed. Keep in mind that tf has a tree structure. Thus, poi_frame_id is the base for all mentioned frames.
    • default: false
  • use_ros_axis_orientation Wether to use ROS axis orientations according to ROS REP 103 for body related frames and geographic frames. Body frame directions affect INS lever arms and IMU orientation setup parameters. Geographic frame directions affect orientation Euler angles for INS+GNSS and attitude of dual-antenna GNSS. If use_ros_axis_orientation is set to true, the driver converts between the NED convention (Septentrio: yaw = 0 is north, positive clockwise), and ENU convention (ROS: yaw = 0 is east, positive counterclockwise). There is no conversion when setting this parameter to false and the angles will be consistent with the web GUI in this case.
    • If set to false Septentrios definition is used, i.e., front-right-down body related frames and NED (north-east-down) for orientation frames.
    • If set to true ROS definition is used, i.e., front-left-up body related frames and ENU (east-north-up) for orientation frames.
    • default: true

UTM zone locking + lock_utm_zone: wether the UTM zone of the initial localization is locked, i.e., this zone is kept even if a zone transition would occur. + default: true

Datum

  • datum: With this command, the datum the coordinates should refer to is selected. With setting it to Default, the datum depends on the positioning mode, e.g. WGS84 for standalone positioning.
    • Since the standardized GGA message does only provide the orthometric height (= MSL height = distance from Earth's surface to geoid) and the geoid undulation (distance from geoid to ellipsoid) for which non-WGS84 datums cannot be specified, it does not affect the GGA message.
    • default: Default

POI-ARP Offset

+ `poi_to_arp`: offsets of the main GNSS antenna reference point (ARP) with respect to the point of interest (POI = marker). Use for static receivers only.
+ The parameters `delta_e`, `delta_n` and `delta_u` are the offsets in the East, North and Up (ENU) directions respectively, expressed in meters.
+ All absolute positions reported by the receiver are POI positions, obtained by subtracting this offset from the ARP. The purpose is to take into account the fact that the antenna may not be located directly on the surveying POI.
+ default: `0.0`, `0.0` and `0.0`

Antenna Attitude Offset

+ `att_offset`: Angular offset between two antennas (Main and Aux) and vehicle frame
+ `heading`: The perpendicular (azimuth) axis can be compensated for by adjusting the `heading` parameter
+ `pitch`: Vertical (elevation) offset can be compensated for by adjusting the `pitch` parameter
+ default: `0.0`, `0.0` (degrees)

Antenna Specs

  • ant_type: type of your main GNSS antenna
    • For best positional accuracy, it is recommended to select a type from the list returned by the command lstAntennaInfo, Overview. This is the list of antennas for which the receiver can compensate for phase center variation.
    • By default and if ant_type does not match any entry in the list returned by lstAntennaInfo, Overview, the receiver will assume that the phase center variation is zero at all elevations and frequency bands, and the position will not be as accurate.
    • default: Unknown
  • ant_serial_nr: serial number of your main GNSS antenna
  • ant_aux1_type and ant_aux1_serial_nr: same for Aux1 antenna

Leap Seconds

  • leap_seconds: Leap seconds are automatically gathered from the receiver via the SBF block ReceiverTime. If a log file is used for simulation and this block was not recorded, the number of leap seconds that have been inserted up until the point of ROSaic usage can be set by this parameter.
    • At the time of writing the code (2020), the GPS time, which is unaffected by leap seconds, was ahead of UTC time by 18 leap seconds. Adapt the leap_seconds parameter accordingly as soon as the next leap second is inserted into the UTC time or in case you are using ROSaic for the purpose of simulations.

Polling Periods

  • polling_period.pvt: desired period in milliseconds between the polling of two consecutive PVTGeodetic, PosCovGeodetic, PVTCartesian and PosCovCartesian blocks and - if published - between the publishing of two of the corresponding ROS messages (e.g. septentrio_gnss_driver/PVTGeodetic.msg). Consult firmware manual for allowed periods. If the period is set to a lower value than the receiver is capable of, it will be published with the next higher period. If set to 0, the SBF blocks are output at their natural renewal rate (OnChange).
  • polling_period.rest: desired period in milliseconds between the polling of all other SBF blocks and NMEA sentences not addressed by the previous parameter, and - if published - between the publishing of all other ROS messages
    • default: 500 (2 Hz)

Time Systems

  • use_gnss_time: true if the ROS message headers' unix epoch time field shall be constructed from the TOW/WNC (in the SBF case) and UTC (in the NMEA case) data, false if those times shall be taken by the driver from ROS time. If use_gnss_time is set to true, make sure the ROS system is synchronized to an NTP time server either via internet or ideally via the Septentrio receiver since the latter serves as a Stratum 1 time server not dependent on an internet connection. The NTP server of the receiver is automatically activated on the Septentrio receiver (for INS/GNSS a firmware >= 1.3.3 is needed).
    • default: true
  • latency_compensation: Rx reports processing latency in PVT and INS blocks. If set to truethis latency is subtracted from ROS timestamps in related blocks (i.e., use_gnss_time set to false). Related blocks are INS, PVT, Covariances, and BaseVectors. In case of use_gnss_time set to true, the latency is already compensated within the RX and included in the reported timestamps.
    • default: false

RTK corrections

  • rtk_settings: determines RTK connection parameters
    • There are multiple possibilities to feed RTK corrections to the Rx. They may be set simultaneously and the Rx will choose the nearest source.
      • a) ntrip_# if the Rx has internet access and is able to receieve NTRIP streams from a caster. Up to three NTRIP connections are possible.
      • b) ip_server_# if corrections are to be receieved via TCP/IP for example over Data Link from Septentrio's RxTools is installed on a computer. Up to five IP server connections are possible.
      • c) serial_# if corrections are to be receieved via a serial port for example over radio link from a local RTK base or over Data Link from Septentrio's RxTools installed on a computer. Up to five serial connections are possible.
    • ntrip_#: for receiving corretions from an NTRIP caster (# is from 1 ... 3).
      • id: NTRIP connection NTR1, NTR2, or NTR3.
      • default: ""
      • caster: is the hostname or IP address of the NTRIP caster to connect to.
      • default: ""
      • caster_port: IP port of the NTRIP caster.
      • default: 2021
      • username: user name for the NTRIP caster.
      • default: ""
      • pasword: password for the NTRIP caster. The receiver encrypts the password so that it cannot be read back with the command "getNtripSettings".
      • default: ""
      • mountpoint: mount point of the NTRP caster to be used.
      • default: ""
      • version: argument specifies which version of the NTRIP protocol to use (v1 or v2).
      • default: "v2"
      • tls: determines wether to use TLS.
      • default: false
      • fingerprint: fingerprint to be used if the certificate is self-signed. If the caster’s certificate is known by a publicly-trusted certification authority, fingerprint should be left empty.
      • default: ""
      • rtk_standard: determines the RTK standard, options are auto, RTCMv2, RTCMv3, or CMRv2.
      • default: "auto"
      • send_gga: specifies whether or not to send NMEA GGA messages to the NTRIP caster, and at which rate. It must be one of auto, off, sec1, sec5, sec10 or sec60. In auto mode, the receiver automatically sends GGA messages if requested by the caster.
      • default: "auto"
      • keep_open: determines wether this connection shall be kept open. If set to true the Rx will still be able to receive RTK corrections to improve precision after driver is shut down.
      • default: true
    • ip_server_#: for receiving corretions via TCP/IP (# is from 1 ... 5).
      • id: specifies the IP server IPS1, IPS2, IPS3, IPS4, or IPS5. Note that ROSaic will send GGA messages on this connection if send_gga is set, such that in the Data Link application of RxTools one just needs to set up a TCP client to the host name as found in the ROSaic parameter device with the port as found in port. If the latter connection were connection 1 on Data Link, then connection 2 would set up an NTRIP client connecting to the NTRIP caster as specified in the above parameters in order to forward the corrections from connection 2 to connection 1.
      • default: ""
      • port: its port number of the connection that ROSaic establishes on the receiver. When selecting a port number, make sure to avoid conflicts with other services.
      • default: 0
      • rtk_standard: determines the RTK standard, options are auto, RTCMv2, RTCMv3, or CMRv2.
      • default: ""
      • send_gga: specifies whether or not to send NMEA GGA messages to the NTRIP caster, and at which rate. It must be one of auto, off, sec1, sec5, sec10 or sec60. In auto mode, the receiver sends with sec1.
      • default: "auto"
      • keep_open: determines wether this connection shall be kept open. If set to true the Rx will still be able to receive RTK corrections to improve precision after driver is shut down.
      • default: true
    • serial_#: for receiving corretions via serial connection (# is from 1 ... 5).
      • port: Serial connection COM1, COM2, COM3, USB1, or USB2 on which corrections could be forwarded to the Rx from a serially connected radio link modem or via Data Link for example.
      • default: ""
      • baud_rate: sets the baud rate of this port for genuine serial ports, i.e., not relevant for USB connection.
      • default: 115200
      • rtk_standard: determines the RTK standard, options are auto, RTCMv2, RTCMv3, or CMRv2.
      • default: "auto"
      • send_gga: specifies whether or not to send NMEA GGA messages to the NTRIP caster, and at which rate. It must be one of auto, off, sec1, sec5, sec10 or sec60. In auto mode, the receiver sends with sec1.
      • default: "auto"
      • keep_open: determines wether this connection shall be kept open. If set to true the Rx will still be able to receive RTK corrections to improve precision after driver is shut down.
      • default: true

INS Specs

+ `ins_spatial_config`: Spatial configuration of INS/IMU. Coordinates according to vehicle related frame directions chosen by `use_ros_axis_orientation` (front-left-up if `true` and front-right-down if `false`).
  + `imu_orientation`: IMU sensor orientation
    + Parameters `theta_x`, `theta_y` and `theta_z` are used to determine the sensor orientation with respect to the vehicle frame. Positive angles correspond to a right-handed (clockwise) rotation of the IMU with respect to its nominal orientation (see below). The order of the rotations is as follows: `theta_z` first, then `theta_y`, then `theta_x`.
    + The nominal orientation is where the IMU is upside down and with the `X axis` marked on the receiver pointing to the front of the vehicle. By contrast, for `use_ros_axis_orientation: true`, nominal orientation is where the `Z axis` of the IMU is pointing upwards and also with the `X axis` marked on the receiver pointing to the front of the vehicle.
    + default: `0.0`, `0.0`, `0.0` (degrees)
  + `poi_lever_arm`: The lever arm from the IMU reference point to a user-defined POI
    + Parameters `delta_x`,`delta_y` and `delta_z` refer to the vehicle reference frame
    + default: `0.0`, `0.0`, `0.0` (meters)
  + `ant_lever_arm`: The lever arm from the IMU reference point to the main GNSS antenna
    + The parameters `x`,`y` and `z` refer to the vehicle reference frame
    + default: `0.0`, `0.0`, `0.0` (meters)
  + `vsm_lever_arm`: The lever arm from the IMU reference point to the velocity sensor
    + The parameters `vsm_x`,`vsm_y` and `vsm_z` refer to the vehicle reference frame 
    + default: `0.0`, `0.0`, `0.0` (meters)
+ `ins_initial_heading`: How the receiver obtains the initial INS/GNSS integrated heading during the alignment phase
    + In case it is `auto`, the initial integrated heading is determined from GNSS measurements.
    + In case it is `stored`, the last known heading when the vehicle stopped before switching off the receiver is used as initial heading. Use if vehicle does not move when the receiver is switched off.
    + default: `auto`
+ `ins_std_dev_mask`: Maximum accepted error
  + `att_std_dev`: Configures an output limit on standard deviation of the attitude angles (max error accepted: 5 degrees)
  + `pos_std_dev`: Configures an output limit on standard deviation of the position (max error accepted: 100 meters)
  + default: `5` degrees, `10` meters    
+ `ins_use_poi`: Whether or not to use the POI defined in `ins_spatial_config.poi_lever_arm`
  + If true, the point at which the INS navigation solution (e.g. in `insnavgeod` ROS topic) is calculated will be the POI as defined above (`poi_frame_id`), otherwise it'll be the main GNSS antenna (`frame_id`). Has to be set to `true` if tf shall be published.
  + default: `true`
+ `ins_vsm`: Configuration of the velocity sensor measurements.
  + `ros`: VSM info received from ROS msgs
    + `source`: Specifies which ROS message type shall be used, options are `odometry` or `twist`. Accordingly, a subscriber is established of the type [`nav_msgs/Odometry.msg`](https://docs.ros2.org/foxy/api/nav_msgs/msg/Odometry.html) or [`geometry_msgs/TwistWithCovarianceStamped.msg`](https://docs.ros2.org/foxy/api/geometry_msgs/msg/TwistWithCovarianceStamped.html) listening on the topics `odometry_vsm` or `twist_vsm` respectively. Only linear velocities are evaluated. Measurements have to be with respect to the frame aligned with the vehicle and defined by `ins_spatial_config.vsm_lever_arm` or tf-frame `vsm_frame_id`, see also comment in [`nav_msgs/Odometry.msg`](https://docs.ros2.org/foxy/api/nav_msgs/msg/Odometry.html) that twist should be specified in `child_frame_id`.
      + default: ""
    + `config`: Defines which measurements belonging to the respective axes are forwarded to the INS. In addition, non-holonomic constraints may be introduced for directions known to be restricted in movement. For example, a vehicle with Ackermann steering is limited in its sidewards and upwards movement. So, even if only motion in x-direction may be measured, zero-velocities for y and z may be sent. Only has to be set if `ins_vsm.ros.source`is set to `odometry` or `twist`.
      + default: []
    + `variances_by_parameter`: Wether variances shall be entered by parameter `ins_vsm.ros.variances` or the values from inside the ROS messages are used. Only has to be set if `ins_vsm.source`is set to `odometry` or `twist`.
      + default: false
    + `variances`: Variances of the respective axes. Only have to be set if `ins_vsm.variances_by_parameter` is set to `true`. Values must be > 0.0, else measurements cannot not be used.
      + default: []
  + `ip_server`:
    + `id`: IP server to receive the VSM info (e.g. `IPS2`).
        + default: ""
    + `port`: TCP port to receive the VSM info. When selecting a port number, make sure to avoid conflicts with other services.
      + default: 0
    + `keep_open` determines wether this connections to receive VSM shall be kept open on driver shutdown. If set to `true` the Rx will still be able to use external VSM info to improve its localization.
      + default: `true`
  + `serial`:
    + `port`: Serial port to receive the VSM info.
      + default: ""
    + `baud_rate`: Baud rate of the serial port to receive the VSM info.
      + default: 115200
    + `keep_open` determines wether this connections to receive VSM shall be kept open on driver shutdown. If set to `true` the Rx will still be able to use external VSM info to improve its localization.
      + default: `true`

Logger

+ `activate_debug_log`: `true` if ROS logger level shall be set to debug.

  • Parameters Configuring (Non-)Publishing of ROS Messages

    NMEA/SBF Messages to be Published

    • publish.gpgga: true to publish nmea_msgs/GPGGA.msg messages into the topic /gpgga
    • publish.gprmc: true to publish nmea_msgs/GPRMC.msg messages into the topic /gprmc
    • publish.gpgsa: true to publish nmea_msgs/GPGSA.msg messages into the topic /gpgsa
    • publish.gpgsv: true to publish nmea_msgs/GPGSV.msg messages into the topic /gpgsv
    • publish.measepoch: true to publish septentrio_gnss_driver/MeasEpoch.msg messages into the topic /measepoch
    • publish.galauthstatus: true to publish septentrio_gnss_driver/GALAuthStatus.msg messages into the topic /galauthstatus and corresponding /diganostics
    • publish.aimplusstatus: true to publish septentrio_gnss_driver/RFStatus.msg messages into the topic /rfstatus, septentrio_gnss_driver/AIMPlusStatus.msg messages into /aimplusstatus and corresponding /diganostics. Some information is only available with active OSNMA.
    • publish.pvtcartesian: true to publish septentrio_gnss_driver/PVTCartesian.msg messages into the topic /pvtcartesian
    • publish.pvtgeodetic: true to publish septentrio_gnss_driver/PVTGeodetic.msg messages into the topic /pvtgeodetic
    • publish.basevectorcart: true to publish septentrio_gnss_driver/BaseVectorCart.msg messages into the topic /basevectorcart
    • publish.basevectorgeod: true to publish septentrio_gnss_driver/BaseVectorGeod.msg messages into the topic /basevectorgeod
    • publish.poscovcartesian: true to publish septentrio_gnss_driver/PosCovCartesian.msg messages into the topic /poscovcartesian
    • publish.poscovgeodetic: true to publish septentrio_gnss_driver/PosCovGeodetic.msg messages into the topic /poscovgeodetic
    • publish.velcovcartesian: true to publish septentrio_gnss_driver/VelCovCartesian.msg messages into the topic /velcovcartesian
    • publish.velcovgeodetic: true to publish septentrio_gnss_driver/VelCovGeodetic.msg messages into the topic /velcovgeodetic
    • publish.atteuler: true to publish septentrio_gnss_driver/AttEuler.msg messages into the topic /atteuler
    • publish.attcoveuler: true to publish septentrio_gnss_driver/AttCovEuler.msg messages into the topic /attcoveuler
    • publish.gpst: true to publish sensor_msgs/TimeReference.msg messages into the topic /gpst
    • publish.navsatfix: true to publish sensor_msgs/NavSatFix.msg messages into the topic /navsatfix
    • publish.gpsfix: true to publish gps_msgs/GPSFix.msg messages into the topic /gpsfix
    • publish.pose: true to publish geometry_msgs/PoseWithCovarianceStamped.msg messages into the topic /pose
    • publish.twist: true to publish geometry_msgs/TwistWithCovarianceStamped.msg messages into the topics /twist and /twist_ins respectively
    • publish.diagnostics: true to publish diagnostic_msgs/DiagnosticArray.msg messages into the topic /diagnostics
    • publish.insnavcart: true to publish septentrio_gnss_driver/INSNavCart.msg message into the topic/insnavcart
    • publish.insnavgeod: true to publish septentrio_gnss_driver/INSNavGeod.msg message into the topic/insnavgeod
    • publish.extsensormeas: true to publish septentrio_gnss_driver/ExtSensorMeas.msg message into the topic/extsensormeas
    • publish.imusetup: true to publish septentrio_gnss_driver/IMUSetup.msg message into the topic/imusetup
    • publish.velsensorsetup: true to publish septentrio_gnss_driver/VelSensorSetup.msgs message into the topic/velsensorsetup
    • publish.exteventinsnavcart: true to publish septentrio_gnss_driver/ExtEventINSNavCart.msgs message into the topic/exteventinsnavcart
    • publish.exteventinsnavgeod: true to publish septentrio_gnss_driver/ExtEventINSNavGeod.msgs message into the topic/exteventinsnavgeod
    • publish.imu: true to publish sensor_msgs/Imu.msg message into the topic/imu
    • publish.localization: true to publish nav_msgs/Odometry.msg message into the topic/localization
    • publish.tf: true to broadcast tf of localization. ins_use_poi must also be set to true to publish tf. Note that only one of publish.tf or publish.tf_ecef may be true.
    • publish.localization_ecef: true to publish nav_msgs/Odometry.msg message into the topic/localization related to ECEF frame.
    • publish.tf_ecef: true to broadcast tf of localization related to ECEF frame. ins_use_poi must also be set to true to publish tf. Note that only one of publish.tf or publish.tf_ecef may be true.

ROS Topic Publications

A selection of NMEA sentences, the majority being standardized sentences, and proprietary SBF blocks is translated into ROS messages, partly generic and partly custom, and can be published at the discretion of the user into the following ROS topics. All published ROS messages, even custom ones, start with a ROS generic header std_msgs/Header.msg, which includes the receiver time stamp as well as the frame ID, the latter being specified in the ROS parameter frame_id.

Available ROS Topics

  • /gpgga: publishes nmea_msgs/Gpgga.msg - converted from the NMEA sentence GGA.
  • /gprmc: publishes nmea_msgs/Gprmc.msg - converted from the NMEA sentence RMC.
  • /gpgsa: publishes nmea_msgs/Gpgsa.msg - converted from the NMEA sentence GSA.
  • /gpgsv: publishes nmea_msgs/Gpgsv.msg - converted from the NMEA sentence GSV.
  • /measepoch: publishes custom ROS message septentrio_gnss_driver/MeasEpoch.msg, corresponding to the SBF block MeasEpoch.
  • /galauthstatus: publishes custom ROS message septentrio_gnss_driver/GALAuthStatus.msg, corresponding to the SBF block GALAuthStatus.
  • /rfstatus: publishes custom ROS message septentrio_gnss_driver/RFStatus.msg, compiled from the SBF block RFStatus.
  • /aimplusstatus: publishes custom ROS message septentrio_gnss_driver/AIMPlusStatus.msg, reporting status of AIM+. Converted from SBF blocks RFStatus and optionally GALAuthStatus. For the latter OSNMA has to be activated.
  • /pvtcartesian: publishes custom ROS message septentrio_gnss_driver/PVTCartesian.msg, corresponding to the SBF block PVTCartesian (GNSS case) or INSNavGeod (INS case).
  • /pvtgeodetic: publishes custom ROS message septentrio_gnss_driver/PVTGeodetic.msg, corresponding to the SBF block PVTGeodetic (GNSS case) or INSNavGeod (INS case).
  • /basevectorcart: publishes custom ROS message septentrio_gnss_driver/BaseVectorCart.msg, corresponding to the SBF block BaseVectorCart.
  • /basevectorgeod: publishes custom ROS message septentrio_gnss_driver/BaseVectorGeod.msg, corresponding to the SBF block BaseVectorGeod.
  • /poscovcartesian: publishes custom ROS message septentrio_gnss_driver/PosCovCartesian.msg, corresponding to SBF block PosCovCartesian (GNSS case) or INSNavGeod (INS case).
  • /poscovgeodetic: publishes custom ROS message septentrio_gnss_driver/PosCovGeodetic.msg, corresponding to SBF block PosCovGeodetic (GNSS case) or INSNavGeod (INS case).
  • /velcovcartesian: publishes custom ROS message septentrio_gnss_driver/VelCovCartesian.msg, corresponding to SBF block VelCovCartesian (GNSS case).
  • /velcovgeodetic: publishes custom ROS message septentrio_gnss_driver/VelCovGeodetic.msg, corresponding to SBF block VelCovGeodetic (GNSS case).
  • /atteuler: publishes custom ROS message septentrio_gnss_driver/AttEuler.msg, corresponding to SBF block AttEuler.
  • /attcoveuler: publishes custom ROS message septentrio_gnss_driver/AttCovEuler.msg, corresponding to the SBF block AttCovEuler.
  • /gpst (for GPS Time): publishes generic ROS message sensor_msgs/TimeReference.msg, converted from the PVTGeodetic (GNSS case) or INSNavGeod (INS case) block's GPS time information, stored in its block header.
  • /navsatfix: publishes generic ROS message sensor_msgs/NavSatFix.msg, converted from the SBF blocks PVTGeodetic,PosCovGeodetic (GNSS case) or INSNavGeod (INS case)
  • /gpsfix: publishes generic ROS message gps_msgs/GPSFix.msg, which is much more detailed than sensor_msgs/NavSatFix.msg, converted from the SBF blocks PVTGeodetic, PosCovGeodetic, ChannelStatus, MeasEpoch, AttEuler, AttCovEuler, VelCovGeodetic, DOP (GNSS case) or INSNavGeod, DOP (INS case). In order to publish heading information, the field dip is diverted from its intended meaning an populated with the heading angle and err_dip with its uncertainty.
  • /pose: publishes generic ROS message geometry_msgs/PoseWithCovarianceStamped.msg, converted from the SBF blocks PVTGeodetic, PosCovGeodetic, AttEuler, AttCovEuler (GNSS case) or INSNavGeod (INS case).
    • Note that GNSS provides absolute positioning, while robots are often localized within a local level cartesian frame. The pose field of this ROS message contains position with respect to the absolute ENU frame (longitude, latitude, height), i.e. not a cartesian frame, while the orientation is with respect to a vehicle-fixed (e.g. for mosaic-x5 in moving base mode via the command setAttitudeOffset, ...) !local! NED frame or ENU frame if use_ros_axis_directions is set true. Thus the orientation is !not! given with respect to the same frame as the position is given in. The cross-covariances are hence set to 0.
  • /twist: publishes generic ROS message geometry_msgs/TwistWithCovarianceStamped.msg, converted from the SBF blocks PVTGeodetic and VelCovGeodetic.
  • /twist_ins: publishes generic ROS message geometry_msgs/TwistWithCovarianceStamped.msg, converted from SBF block INSNavGeod.
  • /insnavcart: publishes custom ROS message septentrio_gnss_driver/INSNavCart.msg, corresponding to SBF block INSNavCart
  • /insnavgeod: publishes custom ROS message septentrio_gnss_driver/INSNavGeod.msg, corresponding to SBF block INSNavGeod
  • /extsensormeas: publishes custom ROS message septentrio_gnss_driver/ExtSensorMeas.msg, corresponding to SBF block ExtSensorMeas.
  • /imusetup: publishes custom ROS message septentrio_gnss_driver/IMUSetup.msg, corresponding to SBF block IMUSetup.
  • /velsensorsetup: publishes custom ROS message septentrio_gnss_driver/VelSensorSetup.msg corresponding to SBF block VelSensorSetup.
  • /exteventinsnavcart: publishes custom ROS message septentrio_gnss_driver/INSNavCart.msg, corresponding to SBF block ExtEventINSNavCart.
  • /exteventinsnavgeod: publishes custom ROS message septentrio_gnss_driver/INSNavGeod.msg, corresponding to SBF block ExtEventINSNavGeod.
  • /diagnostics: accepts generic ROS message diagnostic_msgs/DiagnosticArray.msg, converted from the SBF blocks QualityInd, ReceiverStatus and ReceiverSetup
  • /imu: accepts generic ROS message sensor_msgs/Imu.msg, converted from the SBF blocks ExtSensorMeas and INSNavGeod.
    • The ROS message sensor_msgs/Imu.msg can be fed directly into the robot_localization of the ROS navigation stack. Note that use_ros_axis_orientation should be set to true to adhere to the ENU convention.
  • /localization: accepts generic ROS message nav_msgs/Odometry.msg, converted from the SBF block INSNavGeod and transformed to UTM.
    • The ROS message nav_msgs/Odometry.msg can be fed directly into the robot_localization of the ROS navigation stack. Note that use_ros_axis_orientation should be set to true to adhere to the ENU convention.
  • /localization_ecef: accepts generic ROS message nav_msgs/Odometry.msg, converted from the SBF blocks INSNavCart and INSNavGeod.
    • The ROS message nav_msgs/Odometry.msg can be fed directly into the robot_localization of the ROS navigation stack. Note that use_ros_axis_orientation should be set to true to adhere to the ENU convention.

Suggestions for Improvements

Some Ideas + Equip ROSaic with an NTRIP client such that it can forward corrections to the receiver independently of `Data Link`.

Adding New SBF Blocks or NMEA Sentences

Steps to Follow Is there an SBF or NMEA message that is not being addressed while being important to your application? If yes, follow these steps: 1. Find the log reference of interest in the publicly accessible, official documentation. Hence select the reference guide file, e.g. for mosaic-x5 in the [product support section for mosaic-X5](https://www.septentrio.com/en/support/mosaic/mosaic-x5), Chapter 4, of Septentrio's homepage. 2. SBF: Add a new `.msg` file to the `../msg` folder. And modify the `../CMakeLists.txt` file by adding a new entry to the `add_message_files` section. 3. Add msg header and typedef to `typedefs.hpp`. 4. Parsers: - SBF: Add a parser to the `sbf_blocks.hpp` file. - NMEA: Construct two new parsing files such as `gpgga.cpp` to the `../src/septentrio_gnss_driver/parsers/nmea_parsers` folder and one such as `gpgga.hpp` to the `../include/septentrio_gnss_driver/parsers/nmea_parsers` folder. 5. Processing the message/block: - SBF: Extend the `SbfId` enumeration in the `message_handler.hpp` file with a new entry. - SBF: Extend the SBF switch-case in `message_handler.cpp` file with a new case. - NMEA: Extend the `nmeaMap_` in the `message_handler.hpp` file with a new pair. - NMEA: Extend the NMEA switch-case in `message_handler.cpp` file with a new case. 6. Create a new `publish/..` ROSaic parameter in the `../config/rover.yaml` file and create a boolean variable `publish_xxx` in the struct in the `settings.h` file. Parse the parameter in the `rosaic_node.cpp` file. 7. Add SBF block or NMEA to data stream setup in `communication_core.cpp` (function `configureRx()`).
CHANGELOG

Changelog for package septentrio_gnss_driver

1.3.2 (2022-11-19) -----------* Merge pull request #106 from thomasemter/dev/next2 Fix IMU units * Fix topics namespace * Fix units of imu angular rates * Merge pull request #96 from septentrio-gnss/dev2 Dev2 * Contributors: Thomas Emter, Tibor Dome, septentrio-users

1.3.1 (2022-07-06)

  • New Features

    : - Recovery from connection interruption - Add option to bypass configuration of Rx - Add tests - OSNMA - Latency compensation for ROS timestamps - Output of SBf block VelCovCartesian - Support for UDP and TCP via IP server - New VSM handling allows for unknown variances (INS firmware >= 1.4.1) - Add heading angle to GPSFix msg (by diverting dip field, cf. readme)

  • Improvements

    : - Rework IO core and message handling - Unified stream processing - Internal data queue - Prevent message loss in file reading - Add some explanatory warnings for parameter mismatches - Add units to message definitions

  • Fixes

    : - navsatfix for INS - Empty headers - Single antenna receiver setup

  • Preliminary Features

    : - Output of localization and tf in ECEF frame, testing and feedback welcome

  • Commits

    : - Merge pull request #83 from thomasemter/dev/next2 Update readme - Add expected release dates - Add known issues to readme - Update version - Update readme - Merge pull request #82 from thomasemter/dev/next2 Fix spelling - Categorize stream params - Add keep alive check for TCP - Fix spelling - Add TCP communication via static IP server - Add units to msgs - Fix spelling - Merge pull request #76 from thomasemter/dev/next2 upcoming release - Add heading to GPSFix msg - Move constant - Change log level of firmware check - Add improved VSM handling - Change INS in GNSS node detection to auto - Fix invald v_x var case - Refine readme on UDP - Improve server duplicate check - Add more info un UDP configuration - Fix publish check - Add more publishing checks for configured Rx - Add const for max udp packet size - Update readme and changelog - Add device check to node - Fix param name separators - Add checks for IP server duplicates - Add latency compensation to att msgs - Add device check logic - Add UDP params and setup logic - Fix multi msg per packet - Fix localization stamp and tf publishing - Change VSM to be averaged and published with 2 Hz - Change VSM to be averaged and published with 2 Hz - Always publish raw IMU data as indicated - Change to empty fields - Refine diagnostics naming scheme and add trigger to ensure emission of ReceiverSetup - Change diagnostics naming scheme - Add missing new params to gnss.yaml - Expand readme on AIM+ - Reformulate readme about ROS and ROS2 - Add custom message to report AIM+ status - Catch invalid UTM conversion - Robustify command reset - Add RFStatus diagnostics - Add VelCovCartesian output - Refine Rx type check - Add option for latency compensation - Fix param type misinterpretation - Add OSNMA msg and diagnostics - Update changelog - Refine README and fix compiled message logic - Update changelog - Add warning for configuring INS as GNSS - Add warn log for misconfiguration - Fix pose publishing rate - Fix navsatfix publishing - Make vars const - Merge rework of internal IO handling - Change connection thread - Fix attitude cov flipped twice - Add cov alignment from true north to grid north - Rename meridian convergence and fix sense - Remove obsolete define - Add tests - Rename example launch files so they are found by auto-completion - Merge branch \'dev/ros2\' into dev/next2 - Fix lat/long in rad - Fix readme concerning ROS 2 distros - Reorder localization msg filling - Update readme - Fix NED to ECEF rotation matrix - Add localization ECEF publishing - Add ecef localization msg - Add local to ecef transforms - Contributors: Thomas Emter, Tibor Dome

1.2.3 (2022-11-09)

  • New Features

    : - Twist output option - Example config files for GNSS and INS - Get leap seconds from receiver - Firmware check - VSM from odometry or twist ROS messages - Add receiver type in case INS is used in GNSS mode - Add publishing of base vector topics

  • Improvements

    : - Rework RTK corrections parameters and improve flexibility

  • Fixes

    : - /tf not being published without /localization - Twist covariance matrix of localization - Support 5 ms period for IMU explicitly

1.2.2 (2022-06-22)

  • Fixes

    : - Memory corruption under adverse conditions

  • Commits

    : - Merge pull request #66 from thomasemter/dev/next2 Fix memory corruption - Fix parameter warnings - Reset buffer size to 16384 - Update changelog - Fix memory corruption - Replace maps with unordered_maps - Overload timestamp function - Fix frame ids for INS msgs - Add define to avoid usage of deprecated header - Change readme on gps-msgs packet - Add info on user credentials - Fix spelling in readme - Merge remote-tracking branch \'upstream/ros2\' into dev/next2 - Add comment for heading from pose - Contributors: Thomas Emter, Tibor Dome

1.2.1 (2022-05-16)

  • New Features

    : - Add login credentials - Activate NTP server if use_gnss_time is set to true

  • Improvements

    : - Add NED option to localization

  • Fixes

    : - IMU orientation for ROS axis convention

  • Commits

    : - Merge pull request #63 from thomasemter/dev/next2 Small fixes and additions - Merge pull request #60 from wep21/support-rolling fix: modify build error for rolling/humble - Revert change for deprecation warning in Humble - Change links to reflect ROS2 - Amend readme regarding robot_localization - Fix compiler warnings for humble - Add more explanations for IMU orientation in ROS convention - Fix formatting in readme - Fix package name in readme - Update readme - Update changelog - Fix IMU orientation for ROS axis orientation - Activate NTP only if GNSS time is used - Add NED option to localization - Set NMEA header to GP - Update readme and changelog - Activate NTP server - Add credentials for access control - fix: modify build error for rolling/humble - Contributors: Daisuke Nishimatsu, Thomas Emter, Tibor Dome

1.2.0 (2022-04-27)

  • New Features

    : - Add option to use ROS axis orientations according to REP103 - Add frame_id parameters - Add option to get frames from tf - Publishing of cartesian localization in UTM (topic and/or tf) for INS - Publishing of IMU topic for INS - Publishing of MeasEpoch - ROS2 branch

  • Improvements

    : - Add multi antenna option - Increase number of SBF streams - Add option to set polling_period to \"on change\" - Increased buffer size from 8192 to 131072 bytes - Add endianess aware parsers - Only publish topics set to true - Add parameter to switch DEBUG logging on and off - Change GPxxx messages to ROS built-in types - Remove duplicate INS msg types

  • Fixes

    : - Setting of antenna type - Publishing rate interconnections of gpsfix and velcovgeodetic - Missing quotes for antenna type - Broken attitude parsing pose and gpsfix from INS - IMU orientation was not sent to Rx - Graceful shutdown of threads

  • Commits

    : - Merge branch \'dev\' - Prepare new release - Prepare new release - Merge pull request #53 from thomasemter/dev/refactor Very last changes - Add geographic lib dependency to package.xml - Add comment for frame of main antenna - Move utm zone locking section in readme - Reformulate readme section on frames - Merge pull request #52 from thomasemter/dev/refactor Last changes - Change frame id back to poi_frame_id - Make error log more explicit - Merge pull request #49 from thomasemter/dev/refactor Improve IMU blocks sync and do-not-use value handling - Fix buffer size in changelog - Turn off Nagle\'s algorithm for TCP - Fix changelog formatting - Fix readme - Set default base frame to base_link - Fix valid tow check logic - Increase buffer size for extreme stress tests - Fix crc check - Fix and streamline tf handling - Add checks for validity of values - Fix rad vs deg - Update changelog - Add some comments - Set stdDevMask to values > 0.0 in node - Set stdDevMask to values > 0.0 - Add info on RNDIS and set it to default - Increase default serial baud rate - Add parameter to set log level to debug - Change defaults for publishers in node - Put publish params together and fix mismatch in readme - Improve IMU blocks sync and do-not-use value handling - Merge pull request #48 from thomasemter/dev/refactor Fix measepoch not publishing without gpsfix - Fix measepoch not publishing without gpsfix - Merge pull request #47 from thomasemter/dev/refactor Dev/refactor - Publish only messages set to true - Remove leftover declaration - Merge branch \'dev/endianess_agnostic\' into dev/refactor - Update readme to reflect endianess aware parsing - Remove msg smart pointers - Fix array assertion failure - Cleanup - Add ReceiverStatus parser - Add QualityInd parser - Add DOP parser - Add ReceiverSetup parser - Fix MeasEpoch and ChannelStatus parsers, add measepoch publishing - Add ChannelStatus parser - Add MeasEpoch parser - Add IMU and VelSensor setup parsers - Add Cov SBF parsers - Add templated qi parser function - Add AttEuler+Cov parser - Revert ordering change inside INSNav ROS msgs - Add ExtSensorMeas parser - Add PVT parsers - Add range checks to parsers - Replace INSNav grammar with parsers - Test parser vs. grammar for better performance - Fix sb_list check - Add IMU and VelSensor setup grammars - Move adapt ROS header to typedefs.h - Add revision check to MeasEpoch - Fix ReceiverStatus grammar - Extend ReceiverSetup and add revision checks - Change logger and fix loop range - Remove reserved bytes from parsing - Remove obsolete structs - Directly parse Cov SBFs to ROS msg - Directly parse PVT SBFs, remove obsolete ids - Rename rev to revision - Fix block header parsing - Directly parse AttEuler to ROS msg - Directly parse to ROS msgs for INSNavXxx - Exchange pow with square function and remove casts - Merge pull request #46 from thomasemter/dev/refactor Dev/refactor - Simplify sync bytes check - Move tow/wnc to BlockHeader - Adjust order in INSNav ros msgs - Fix INSNav grammars - Change BlockHeader structure - Remove length ref from header - Rectify sb_list check of INSNavXxx - Add automtatic activation of multi-antenna mode - Merge branch \'dev/refactor\' of https://github.com/thomasemter/septentrio_gnss_driver into dev/refactor - Add automtatic activation of multi-antenna mode - Fix wrong scope of phoenix::ref variables - Fix AttEuler grammar - Add max size checks to QualityInd and ReceiverStatus - Replace locals with phoenix::ref in grammars - Add revision dependent parsing to PVTs - Change offset check to epsilon - Change offset check to epsilon - Fix parsing checks - Set has arrived to false on parsing error - Add INSNav grammars - Add abs to offset check - Add abs to offset check - Add Cov grammars - Remove superfluous typdefs of structs - Add ReceiverStatus grammar - Add QualityINd grammar - Merge pull request #45 from thomasemter/dev/refactor Dev/refactor - Add id check to header grammar - Add id check to header grammar - Add ReceiverSetup grammar - Add DOP grammar - Directly intialize vector to parse - Add MeasEpoch grammar - Remove duplicate msg types - Remove obsolete include - Add revision and length return to header grammar - Merge branch \'feature/endianess_agnostic\' into dev/endianess_agnostic - Make multi_antenna option also usable for gnss - Add typedefs plus some minor changes - Add warning concerning pitch angle if antennas are rotated - Add multi antenna option to ins and fix antenna offset decimal places trimming - Fix identation - Distinguish between gnss and ins for spatial config from tf - Merge pull request #43 from thomasemter/dev/refactor Dev/refactor - Add vehicle frame for clarity - Handle missing tf more gently - Merge branch \'dev/spatial_config_via_tf\' into dev/refactor - Update readme - Fix antenna offset from tf - Add automatic publishing of localization if tf is activated - Add automatic publishing of localization if tf is activated - Add spatial config via tf, to be tested - Fix crashes due to parsing errors (replacing uncatched throws) - Add tf broadcasting - Add comments - Add localization in UTM output - Add check to IMU msg sync - Change msg sync to allow for 200 Hz IMU msgs - Add ROS IMU msg - Fix IMU setup message attitude conversion - Fix pose from INS data - Fix IMU raw data rotation compensation - Make antenna attitude offset usable by GNSS - Add ros directions option to pose and fix covariances - Update readme - Merge branch \'feature/ros_axis_orientation\' into dev/refactor - Add nmea_msgs dependencies - Merge branch \'dev/nmea\' into dev/refactor - Update readme - Update readme - Add antenna offsets to conversions - Fix IMU orientation conversion - Change ExtSensorMead temperature to deg C - Add axis orientation info to readme - Fix IMU axis orientation - Change get int param - Update readme to reflect removal of aux antenna offset - Fix different antenna setup message for INS and remove obsolete aux1 antenna offset for GNSS - Fix ExtSensorMeas message filling - Fix ExtSensorMeas message to reflect available fields - Fix missing INS blocks - Fix missing INS blocks - WIP, introduce ros axis orientation option, to be tested - Add option to set pvt rate to OnChange - Add comment on NTP to readme - Change to nmea_msgs - Add automatic addition of needed sub messages - Comment out setting debug level - Add comments and fix spelling errors - Merge pull request #42 from thomasemter/dev/refactor Dev/refactor - Change to quaternion msg typedef - Comment out debug logging - Remove filling of seq field - Change msg definitions to be compatible with ROS2 - Update readme - Change make_shared for portability and add more typedefs - Add get param int fallback for numeric antenna serial numbers - Change Attitude to be published with pvt rate - Add log identifier - Add checks for relevant ros params - Concatenate multiple SBF blocks in streams - Move main into own file - Move get ros time to AsyncManager - Remove obsolete param comment - Move get ros params to base class - Change to nsec timestamp internally - Add publishing functionality to node base class - Move node handle ptr and functions to base class and rename - Add stamp to nmea parsing - Add logging in PcapReader - Add logging in CircularBuffer - Add missed logging - Add logging in AsyncManager - Add getTime function - Add logging in RxMessage - Add logging in CallbackHandlers - Add log function to node by polymorphism, logging in Comm_OI - Fix wait function and force use_gnss_time when reading from file - Add thread shutdown and remove spurious delete - Add typedefs for ins messages - Add typedefs for gnss messages - Add typedefs for ros messages - Refine shutdown - Fix shutdown escalating to SIGTERM - Move waiting for response in send function - Make functions private - Change crc to C++ - Fix variable name - Remove global variables from node cpp file - Move more global settings to settings struct - Move more global settings to settings struct - Move global settings to settings struct - Move more functions to Comm_IO - Move settings to struct and configuration to Comm_IO - Merge branch \'dev/change_utc_calculation\' into dev/refactor - Remove obsolete global variables - Move g_unix_time to class - Make has_arrived booleans class memebers and rx_message a persistent class - Make node handle a class member - Fix parsing of ID and rev - Finish ChannelStatusGrammar, to be tested - WIP, partially fix ChannelStatusGrammar - Add SBF length parsing utility - Insert spirit parsers - WIP, add omission of padding bytes - WIP, add more spirit parsers - Add parsing utilities for tow, wnc and ID - Move getId/Tow/Wnc to parsing utilities - Change UTC calculation to use tow and wnc - WIP, add boost spirit and endian buffers - Change UTC calculation to use tow and wnc

  • ROS2 Commits

    : - Prepare ros2 release - Merge pull request #54 from thomasemter/dev/ros2 ROS2 branch - Port driver to ros2

  • Change UTC calculation to use tow and wnc

  • Contributors: Thomas Emter, Tibor Dome, tibordome

1.0.8 (2021-10-23)

  • Added INS Support

1.0.7 (2021-05-18)

  • Clang formatting, publishing from SBF log, play-back of PCAP files

1.0.6 (2020-10-16)

  • ROSaic binary installation now available on Melodic & Noetic

1.0.5 (2020-10-15)

  • changed repo name
  • v1.0.4
  • 1.0.3
  • Merge pull request #22 from septentrio-gnss/local_tibor New changelog
  • New changelog
  • Merge pull request #21 from septentrio-gnss/local_tibor Added rosdoc.yaml file
  • Merge pull request #20 from septentrio-gnss/local_tibor Improved doxygen annotations
  • Merge pull request #19 from septentrio-gnss/local_tibor Improved doxygen annotations
  • Update README.md
  • Merge pull request #18 from septentrio-gnss/local_tibor Adopted ROS and C++ conventions, added ROS diagnostics msg,
  • Update README.md
  • Update README.md
  • Update README.md
  • Contributors: septentrio-users, tibordome

1.0.4 (2020-10-11)

  • Added rosdoc.yaml file
  • Improved doxygen annotations
  • Improved doxygen annotations
  • Adopted ROS and C++ conventions, added ROS diagnostics msg, removed ROS garbage value bug, added auto-detection of SBF arrival order for composite ROS msgs
  • Merge branch \'master\' of https://github.com/septentrio-gnss/rosaic
  • NTRIP with Datalink, circular buffer, reading connection descriptor, new messages
  • Update README.md
  • Contributors: septentrio-users, tibordome

1.0.3 (2020-09-30)

  • Add new config/rover.yaml file
  • Add config/rover.yaml to .gitignore
  • Merge pull request #17 from septentrio-gnss/local_tibor NTRIP with Datalink, circular buffer, reading connection descriptor..
  • Merge branch \'local_tibor\'
  • NTRIP with Datalink, circular buffer, reading connection descriptor, new messages
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #16 from septentrio-gnss/local_tibor NTRIP parameters added, reconnect_delay_s implemented,
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #15 from tibordome/local_tibor GPSFix completed, datum as new parameter
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #14 from tibordome/local_tibor GPSFix completed, datum as new parameter
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #13 from tibordome/local_tibor Added AttCovEuler.msg and AttEuler.msg
  • Merge pull request #12 from tibordome/local_tibor Fixed service field of NavSatStatus
  • Contributors: Tibor Dome, septentrio-users, tibordome

1.0.2 (2020-09-25)

  • NTRIP parameters added, reconnect_delay_s implemented, package.xml updated, ROSaic now detects connection descriptor automatically, mosaic serial port parameter added
  • GPSFix completed, datum as new parameter, ANT type and marker-to-arp distances as new parameters, BlockLength() method corrected, sending multiple commands to Rx corrected by means of mutex
  • Contributors: tibordome

1.0.1 (2020-09-22)

  • GPSFix completed, datum as new parameter, ANT type and marker-to-arp distances as new parameters, BlockLength() method corrected, sending multiple commands to Rx corrected by means of mutex
  • Added AttCovEuler.msg and AttEuler.msg
  • Fixed service field of NavSatStatus, fixed ROS header\'s seq field of each published ROS message, added write method for sending commands to Rx, successfully tested, added AttEuler, added AttCovEuler
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #11 from tibordome/local_tibor rosconsole_backend_interface dependency not needed
  • rosconsole_backend_interface dependency not needed
  • Merge pull request #10 from tibordome/local_tibor rosconsole_log4cxx dep not needed
  • rosconsole_log4cxx dep not needed
  • Merge pull request #9 from tibordome/local_tibor rosconsole_log4cxx dep not needed
  • rosconsole_log4cxx dep not needed
  • Merge pull request #8 from tibordome/local_tibor Local tibor
  • Update README.md
  • Merge pull request #7 from tibordome/local_tibor Ready for First Release
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #6 from tibordome/local_tibor Local tibor
  • Merge pull request #5 from tibordome/local_tibor TCP seems to work
  • Contributors: Tibor Dome, tibordome

1.0.0 (2020-09-11)

  • Ready for first release
  • Added Gpgga.msg and PosCovGeodetic.msg files
  • Ready for First Release
  • Ready for first release
  • Ready for first release
  • Ready for first release
  • TCP bug removed
  • TCP bug removed
  • TCP seems to work
  • Merge pull request #4 from tibordome/v0.2 V0.2
  • PVTCartesian and PVTGeodetic publishing works on serial
  • PVTCartesian and PVTGeodetic publishing works on serial
  • Merge pull request #3 from tibordome/v0.2 Add doxygen_out and Doxyfile 2nd trial
  • Add doxygen_out and Doxyfile 2nd trial
  • Merge pull request #2 from tibordome/v0.1 Add doxygen_out and Doxyfile
  • Add doxygen_out and Doxyfile
  • Update README.md
  • Create README.md
  • Update LICENSE
  • Merge pull request #1 from tibordome/add-license-1 Create LICENSE
  • Create LICENSE
  • Create LICENSE
  • Commit
  • Successfully tested publishing to /gpgga topic via serial
  • To make sure master branch exists
  • Contributors: Tibor Dome, tibordome

Wiki Tutorials

See ROS Wiki Tutorials for more details.

Source Tutorials

Not currently indexed.

Recent questions tagged septentrio_gnss_driver at Robotics Stack Exchange

septentrio_gnss_driver package from septentrio_gnss_driver repo

septentrio_gnss_driver

Package Summary

Tags No category tags.
Version 1.3.2
License BSD 3-Clause License
Build type CATKIN
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/septentrio-gnss/septentrio_gnss_driver.git
VCS Type git
VCS Version master
Last Updated 2023-11-19
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

ROSaic: C++ driver for Septentrio's mosaic receivers and beyond

Additional Links

Maintainers

  • Septentrio

Authors

  • Tibor Dome

ROSaic = ROS + mosaic

Overview

This repository hosts drivers for ROS (Melodic and Noetic) and ROS 2 (Foxy, Galactic, Humble, Rolling, and beyond) - written in C++ - that work with mosaic and AsteRx - two of Septentrio's cutting-edge GNSS and GNSS/INS receiver families - and beyond. The ROS version is available in this branch, whereas the ROS 2 version is available in the branch ros2.

Main Features: - Supports Septentrio's single antenna GNSS, dual antenna GNSS and INS receivers - Supports serial, TCP/IP and USB connections, the latter being compatible with both serial (RNDIS) and TCP/IP protocols - Supports several ASCII (including key NMEA ones) messages and SBF (Septentrio Binary Format) blocks - Reports status of AIM+ (Advanced Interference Mitigation including OSNMA) anti-jamming and anti-spoofing. - Can publish nav_msgs/Odometry message for INS receivers - Can blend SBF blocks PVTGeodetic, PosCovGeodetic, ChannelStatus, MeasEpoch, AttEuler, AttCovEuler, VelCovGeodetic and DOP in order to publish gps_common/GPSFix and sensor_msgs/NavSatFix messages - Supports axis convention conversion as Septentrio follows the NED convention, whereas ROS is ENU. - Easy configuration of multiple RTK corrections simultaneously (via NTRIP, TCP/IP stream, or serial) - Can play back PCAP capture logs for testing purposes - Tested with the mosaic-X5, mosaic-H, AsteRx-m3 Pro+ and the AsteRx-SBi3 Pro receiver - Easy to add support for more log types

Please let the maintainers know of your success or failure in using the driver with other devices so we can update this page appropriately.

Dependencies

The master branch for this driver functions on both ROS Melodic (Ubuntu 18.04) and Noetic (Ubuntu 20.04). It is thus necessary to install the ROS version that has been designed for your Linux distro.

Additional ROS packages have to be installed for the GPSFix message.

sudo apt install ros-$ROS_DISTRO-nmea-msgs ros-$ROS_DISTRO-gps-common.

The serial and TCP/IP communication interface of the ROS driver is established by means of the Boost C++ library. In the unlikely event that the below installation instructions fail to install Boost on the fly, please install the Boost libraries via

sudo apt install libboost-all-dev.

Compatiblity with PCAP captures are incorporated through pcap libraries. Install the necessary headers via

sudo apt install libpcap-dev.

Conversions from LLA to UTM are incorporated through GeographicLib. Install the necessary headers via

sudo apt install libgeographic-dev

Usage

Binary Install The binary release is now available for Melodic and Noetic. To install the binary package on Melodic for instance, simply run `sudo apt-get install ros-$ROS_DISTRO-septentrio-gnss-driver`.
Build from Source Alternatively, the package can also be built from source using [`catkin_tools`](https://catkin-tools.readthedocs.io/en/latest/installing.html), where the latter can be installed using the command `sudo apt-get install python-catkin-tools` for Melodic or `sudo apt-get install python3-catkin-tools` for Noetic. The typical `catkin_tools` [workflow](https://catkin-tools.readthedocs.io/en/latest/quick_start.html) should suffice: ``` source /opt/ros/${ROS_DISTRO}/setup.bash # In case you do not use the default shell of Ubuntu, you need to source another script, e.g. setup.sh. mkdir -p ~/septentrio/src # Note: Change accordingly dependending on where you want your package to be installed. cd ~/septentrio catkin init # Initialize with a hidden marker file catkin config --cmake-args -DCMAKE_BUILD_TYPE=RelWithDebInfo # CMake build types pass compiler-specific flags to your compiler. This type amounts to a release with debug info, while keeping debugging symbols and doing optimization. I.e. for GCC the flags would be -O2, -g and -DNDEBUG. cd src git clone https://github.com/septentrio-gnss/septentrio_gnss_driver rosdep install . --from-paths -i # Might raise "rosaic: Unsupported OS [mint]" warning, if your OS is Linux Mint, since rosdep does not know Mint (and possible other OSes). In that case, add the "--os=ubuntu:saucy" option to "fool" rosdep into believing it faces some Ubuntu version. The syntax is "--os=OS_NAME:OS_VERSION". catkin build # If catkin cannot find empy, tell catkin to use Python 3 by adding "-DPYTHON_EXECUTABLE=/usr/bin/python3". echo "source ~/septentrio/devel/setup.bash" >> ~/.bashrc # It is convenient if the ROS environment variable is automatically added to your bash session every time a new shell is launched. Again, this works for bash shells only. Also note that if you have more than one ROS distribution installed, ~/.bashrc must only source the setup.bash for the version you are currently using. source ~/.bashrc ```
Notes Before Usage + In your bash sessions, navigating to the ROSaic package can be achieved from anywhere with no more effort than `roscd septentrio_gnss_driver`. + The driver assumes that our anonymous access to the Rx grants us full control rights. This should be the case by default, and can otherwise be changed with the `setDefaultAccessLevel` command. If user control is in place user credentials can be given by parameters `login/user` and `login/password`. + ROSaic only works from C++11 onwards due to std::to_string() etc. + Once the catkin build or binary installation is finished, adapt the `config/rover.yaml` file according to your needs. The `launch/rover.launch` need not be modified. Specify the communication parameters, the ROS messages to be published, the frequency at which the latter should happen etc.:
+ Note for setting `ant_serial_nr` and `ant_aux1_serial_nr`: This is a string parameter, numeric-only serial numbers should be put in quotes. If this is not done a warning will be issued and the driver tries to parse it as integer. + Besides the aforementioned config file `rover.yaml` containing all parameters, specialized launch files for GNSS `config/gnss.yaml` and INS `config/ins.yaml` respectively contain only the relevant parameters in each case. - NOTE: Unless `configure_rx` is set to `false`, this driver will overwrite the previous values of the parameters, even if the value is left to zero in the "yaml" file. + The driver was developed and tested with firmware versions >= 4.10.0 for GNSS and >= 1.3.2 for INS. Receivers with older firmware versions are supported but some features may not be available. Known limitations are: * GNSS with firmware < 4.10.0 does not support IP over USB. * GNSS with firmware < 4.12.1 does not support OSNMA. * INS with firmware < 1.3.2 does not support NTP. * INS with firmware < 1.4 does not support OSNMA. * INS with firmware < 1.4.1 does not support improved VSM handling allowing for unknown variances. * INS with firmware 1.2.0 does not support velocity aiding. * INS with firmware 1.2.0 does not support setting of initial heading. + Known issues: * UDP over USB: Blocks are sent twice on GNSS with firmware <= 4.12.1 and INS with firmware <= 1.4. For GNSS it is fixed in version 4.14 (released on June 15th 2023), for INS it will be fixed in to-be-released 1.4.1 (expected in November 2023). + If `use_ros_axis_orientation` to `true` axis orientations are converted by the driver between NED (Septentrio: yaw = 0 is north, positive clockwise) and ENU (ROS: yaw = 0 is east, positive counterclockwise). There is no conversion when setting this parameter to `false` and the angles will be consistent with the web GUI. :
``` # Example configuration Settings for the Rover Rx device: tcp://192.168.3.1:28784 serial: baudrate: 921600 hw_flow_control: off stream_device: tcp: ip_server: "" port: 0 udp: ip_server: "" port: 0 unicast_ip: "" configure_rx: true login: user: "" password: "" osnma: mode: "off" ntp_server: "" keep_open: true frame_id: gnss imu_frame_id: imu poi_frame_id: base_link vsm_frame_id: vsm aux1_frame_id: aux1 vehicle_frame_id: base_link insert_local_frame: false local_frame_id: odom get_spatial_config_from_tf: true lock_utm_zone: true use_ros_axis_orientation: false receiver_type: gnss datum: Default poi_to_arp: delta_e: 0.0 delta_n: 0.0 delta_u: 0.0 att_offset: heading: 0.0 pitch: 0.0 ant_type: Unknown ant_aux1_type: Unknown ant_serial_nr: Unknown ant_aux1_serial_nr: Unknown leap_seconds: 18 polling_period: pvt: 500 rest: 500 use_gnss_time: false latency_compensation: false rtk_settings: ntrip_1: id: "NTR1" caster: "1.2.3.4" caster_port: 2101 username: "Asterix" password: "password" mountpoint: "mtpt1" version: "v2" tls: true fingerprint: "AA:BB:56:78:90:12: ... 78:90:12:34" rtk_standard: "RTCMv3" send_gga: "auto" keep_open: true ntrip_2: id: "NTR3" caster: "5.6.7.8" caster_port: 2101 username: "Obelix" password: "password" mountpoint: "mtpt2" version: "v2" tls: false fingerprint: "" rtk_standard: "RTCMv2" send_gga: "auto" keep_open: true ip_server_1: id: "IPS3" port: 28785 rtk_standard: "RTCMv2" send_gga: "auto" keep_open: true ip_server_2: id: "IPS5" port: 28786 rtk_standard: "CMRv2" send_gga: "auto" keep_open: true serial_1: port: "COM1" baud_rate: 230400 rtk_standard: "auto" send_gga: "sec1" keep_open: true serial_2: port: "COM2" baud_rate: 230400 rtk_standard: "auto" send_gga: "off" keep_open: true publish: # For both GNSS and INS Rxs navsatfix: false gpsfix: true gpgga: false gprmc: false gpst: false measepoch: false pvtcartesian: false pvtgeodetic: true basevectorcart: false basevectorgeod: false poscovcartesian: false poscovgeodetic: true velcovcartesian: false velcovgeodetic: false atteuler: true attcoveuler: true pose: false twist: false diagnostics: false aimplusstatus: true galauthstatus: false # For GNSS Rx only gpgsa: false gpgsv: false # For INS Rx only insnavcart: false insnavgeod: false extsensormeas: false imusetup: false velsensorsetup: false exteventinsnavcart: false exteventinsnavgeod: false imu: false localization: false tf: false localization_ecef: false tf_ecef: false # INS-Specific Parameters ins_spatial_config: imu_orientation: theta_x: 0.0 theta_y: 0.0 theta_z: 0.0 poi_lever_arm: delta_x: 0.0 delta_y: 0.0 delta_z: 0.0 ant_lever_arm: x: 0.0 y: 0.0 z: 0.0 vsm_lever_arm: vsm_x: 0.0 vsm_y: 0.0 vsm_z: 0.0 ins_initial_heading: auto ins_std_dev_mask: att_std_dev: 5.0 pos_std_dev: 10.0 ins_use_poi: true ins_vsm: source: "twist" config: [true, false, false] variances_by_parameter: true variances: [0.1, 0.0, 0.0] ip_server: id: "IPS2" port: 28787 keep_open: true serial: port: "COM3" baud_rate: 115200 keep_open: true # Logger activate_debug_log: false ``` In order to launch ROSaic, one must specify all `arg` fields of the `rover.launch` file which have no associated default values, i.e. for now only the `param_file_name` field. Hence, the launch command reads `roslaunch septentrio_gnss_driver rover.launch param_file_name:=rover`.

Inertial Navigation System (INS): Basics

  • An Inertial Navigation System (INS) is a device which takes the rotation and acceleration solutions as obtained from its Inertial Measurement Unit (IMU) and combines those with position and velocity information from the GNSS module. Compared to a GNSS system with 7D or 8D (dual-antenna systems) phase space solutions, the combined, Kalman-filtered 9D phase space solution (3 for position, 3 for velocity, 3 for orientation) of an INS is more accurate, more precise and more stable against GNSS outages.
  • The IMU is typically made up of a 3-axis accelerometer, a 3-axis gyroscope and sometimes a 3-axis magnetometer and measures the system's angular rate and acceleration.

    Measure and Compensate for IMU-Antenna Lever Arm

    • The IMU-antenna lever-arm is the relative position between the IMU reference point and the GNSS Antenna Reference Point (ARP), measured in the vehicle frame.
    • In case of AsteRx SBi3, the IMU reference point is clearly marked on the top panel of the receiver. It is important to compensate for the effect of the lever arm, otherwise the receiver may not be able to calculate an accurate INS position.
    • The IMU/antenna position can be changed by specifying the lever arm's x,yand z parameters in the config.yaml file under the ins_spatial_config/ant_lever_arm parameter.

    Screenshot from 2021-08-03 09-23-19 (1)

    Compensate for IMU Orientation + It is important to take into consideration the mounting direction of the IMU in the body frame of the vehicle. For e.g. when the receiver is installed horizontally with the front panel facing the direction of travel, we must compensate for the IMU’s orientation to make sure the IMU reference frame is aligned with the vehicle reference frame. The IMU position and orientation is printed on the top panel, cf. image below. + The IMU's orientation can be changed by specifying the orientation angles theta_x,theta_yand theta_z in the config.yaml file under the ins_spatial_config/imu_orientation + The below image illustrates the orientation of the IMU reference frame with the associated IMU orientation for the depicted installation. Note that for use_ros_axis_orientation: true sensor_default is the top left position.

    Capture (1)

  • These Steps should be followed to configure the receiver in INS integration mode:

    • Specify receiver_type: ins
    • Specify the orientation of the IMU sensor with respect to your vehicle, using the ins_spatial_config/imu_orientation parameter.
    • Specify the IMU-antenna lever arm in the vehicle reference frame. This is the vector starting from the IMU reference point to the ARP of the main GNSS antenna. This can be done by means of the ins_spatial_config/ant_lever_arm parameter. Specify ins_spatial_config/vsm_lever_arm if measurements of a velocity sensor is available.
    • Alternatively the lever arms may be specified via tf. Set get_spatial_config_from_tfto true in this case.
    • If the point of interest is neither the IMU nor the ARP of the main GNSS antenna, the vector between the IMU and the point of interest can be provided with the ins_solution/poi_lever_arm parameter.
  • For further more information about Septentrio receivers, visit Septentrio support resources or check out the user manual and reference guide of the AsteRx SBi3 receiver.

ROSaic Parameters

The following is a list of ROSaic parameters found in the config/rover.yaml file. * Parameters Configuring Communication Ports and Processing of GNSS and INS Data

Connectivity Specs

  • device: location of main device connection. This interface will be used for setup communication and VSM data for INS. Incoming data streams of SBF blocks and NMEA sentences are recevied either via this interface or a static IP server for TCP and/or UDP. The former will be utilized if section stream_device/tcp and stream_device/udp are not configured.
    • serial:xxx format for serial connections, where xxx is the device node, e.g. serial:/dev/ttyS0. If using serial over USB, it is recommended to specify the port by ID as the Rx may get a different ttyXXX on reconnection, e.g. serial:/dev/serial/by-id/usb-Septentrio_Septentrio_USB_Device_xyz.
    • file_name:path/to/file.sbf format for publishing from an SBF log
    • file_name:path/to/file.pcap format for publishing from PCAP capture.
      • Regarding the file path, ROS_HOME=`pwd` in front of roslaunch septentrio... might be useful to specify that the node should be started using the executable's directory as its working-directory.
    • tcp://host:port format for TCP/IP connections
      • 28784 should be used as the default (command) port for TCP/IP connections. If another port is specified, the receiver needs to be (re-)configured via the Web Interface before ROSaic can be used.
      • An RNDIS IP interface is provided via USB, assigning the address 192.168.3.1 to the receiver. This should work on most modern Linux distributions. To verify successful connection, open a web browser to access the web interface of the receiver using the IP address 192.168.3.1.
    • default: tcp://192.168.3.1:28784
  • serial: specifications for serial communication
    • baudrate: serial baud rate to be used in a serial connection. Ensure the provided rate is sufficient for the chosen SBF blocks. For example, activating MeasEpoch (also necessary for /gpsfix) may require up to almost 400 kBit/s.
    • hw_flow_control: specifies whether the serial (the Rx's COM ports, not USB1 or USB2) connection to the Rx should have UART hardware flow control enabled or not
      • off to disable UART hardware flow control, RTS|CTS to enable it
    • default: 921600, USB1, off
  • stream_device: If left unconfigured, by default device is utilized for the data streams. Within stream_device static IP servers may be defined instead. In config mode (configure_rx set to true), TCP will be prioritized over UDP. If Rx is pre-configured, both may be set simultaneously.
    • tcp: specifications for static TCP server of SBF blocks and NMEA sentences.
      • ip_server: IP server of Rx to be used, e.g. “IPS1”.
      • port: UDP destination port.
    • udp: specifications for low latency UDP reception of SBF blocks and NMEA sentences.
      • ip_server: IP server of Rx to be used, e.g. “IPS1”.
      • port: UDP destination port.
      • unicast_ip: Set to computer's IP to use unicast (optional). If not set multicast will be used.
  • login: credentials for user authentication to perform actions not allowed to anonymous users. Leave empty for anonymous access.
    • user: user name
    • password: password

OSNMA

  • osnma: Configuration of the Open Service Navigation Message Authentication (OSNMA) feature.
    • mode: Three operating modes are supported: off where OSNMA authentication is disabled, loose where satellites are included in the PVT if they are successfully authenticated or if their authentication status is unknown, and strict where only successfully-authenticated satellites are included in the PVT. In case of strict synchronization via NTP is mandatory.
      • default: off
    • ntp_server: In strict mode, OSNMA authentication requires the availability of external time information. In loose mode, this is optional but recommended for enhanced security. The receiver can connect to an NTP time server for this purpose. Options are default to let the receiver choose an NTP server or specify one like pool.ntp.org for example.
      • default: ""
    • keep_open: Wether OSNMA shall be kept active on driver shutdown.
      • default: true

Receiver Configuration

+ configure_rx: Wether to configure the Rx according to the config file. If set to `false`, the Rx has to be configured via the web interface and the settings must be saved. On the driver side communication has to set accordingly to serial, TCP or UDP (TCP and UDP may even be used simultaneously in this case). For TCP communication it is recommended to use a static TCP server (`stream_device/tcp/ip_server` and `stream_device/tcp/port`), since dynamic connections (`device` is tcp) are not guaranteed to have the same id on reconnection. It should also be ensured that obligatory SBF blocks are activated (as of now: ReceiverTime if `use_gnss_time` is set to `true`; `PVTGeodetic`or `PVTCartesian` if latency compensation for PVT related blocks shall be used). Further, if ROS messages compiled from multiple SBF blocks, it should be ensured that all necessary blocks are activated with matching periods, details can be found in section [ROS Topic Publications](#ros-topic-publications). The messages that shall be published still have to be set to `true` in the *NMEA/SBF Messages to be Published* section. Also, parameters concerning the connection and node setup are still relevant (sections: *Connectivity Specs*, *receiver type*, *Frame IDs*, *UTM Zone Locking*, *Time Systems*, *Logger*).
  + default: true

Receiver Type

  • receiver_type: This parameter is to select the type of the Septentrio receiver
    • gnss for GNSS receivers.
    • ins for INS receivers.
    • default: gnss
  • multi_antenna: Whether or not the Rx has multiple antennas.
    • default: false

Frame IDs

  • frame_id: name of the ROS tf frame for the Rx, placed in the header of published GNSS messages. It corresponds to the frame of the main antenna.
    • In ROS, the tf package lets you keep track of multiple coordinate frames over time. The frame ID will be resolved by tf_prefix if defined. If a ROS message has a header (all of those we publish do), the frame ID can be found via rostopic echo /topic, where /topic is the topic into which the message is being published.
    • default: gnss
  • imu_frame_id: name of the ROS tf frame for the IMU, placed in the header of published IMU message
    • default: imu
  • poi_frame_id: name of the ROS tf frame for the POI, placed in the child frame_id of localization if ins_use_poi is set to true.
    • default: base_link
  • vsm_frame_id: name of the ROS tf frame for the velocity sensor.
    • default: vsm
  • aux1_frame_id: name of the ROS tf frame for the aux1 antenna.
    • default: aux1
  • vehicle_frame_id: name of the ROS tf frame for the vehicle. Default is the same as poi_frame_id but may be set otherwise.
    • default: base_link
  • local_frame_id: name of the ROS tf frame for the local frame.
    • default: odom
  • insert_local_frame: Wether to insert a local frame to published tf according to ROS REP 105. The transform from the local frame specified by local_frame_id to the vehicle frame specified by vehicle_frame_id has to be provided, e.g. by odometry. Insertion of the local frame means the transform between local frame and global frame is published instead of transform between vehicle frame and global frame.
    • default: false
  • get_spatial_config_from_tf: wether to get the spatial config via tf with the above mentioned frame ids. This will override spatial settings of the config file. For receiver type ins with multi_antenna set to true all frames have to be provided, with multi_antenna set to false, aux1_frame_id is not necessary. For type gnss with dual-antenna setup only frame_id, aux1_frame_id, and poi_frame_id are needed. For single-antenna gnss no frames are needed. Keep in mind that tf has a tree structure. Thus, poi_frame_id is the base for all mentioned frames.
    • default: false
  • use_ros_axis_orientation Wether to use ROS axis orientations according to ROS REP 103 for body related frames and geographic frames. Body frame directions affect INS lever arms and IMU orientation setup parameters. Geographic frame directions affect orientation Euler angles for INS+GNSS and attitude of dual-antenna GNSS. If use_ros_axis_orientation is set to true, the driver converts between the NED convention (Septentrio: yaw = 0 is north, positive clockwise), and ENU convention (ROS: yaw = 0 is east, positive counterclockwise). There is no conversion when setting this parameter to false and the angles will be consistent with the web GUI in this case.
    • If set to false Septentrios definition is used, i.e., front-right-down body related frames and NED (north-east-down) for orientation frames.
    • If set to true ROS definition is used, i.e., front-left-up body related frames and ENU (east-north-up) for orientation frames.
    • default: true

UTM Zone Locking

  • lock_utm_zone: wether the UTM zone of the initial localization is locked, i.e., this zone is kept even if a zone transition would occur.
    • default: true

Datum

  • datum: With this command, the datum the coordinates should refer to is selected. With setting it to Default, the datum depends on the positioning mode, e.g. WGS84 for standalone positioning.
    • Since the standardized GGA message does only provide the orthometric height (= MSL height = distance from Earth's surface to geoid) and the geoid undulation (distance from geoid to ellipsoid) for which non-WGS84 datums cannot be specified, it does not affect the GGA message.
    • default: Default

POI-ARP Offset

  • poi_to_arp: offsets of the main GNSS antenna reference point (ARP) with respect to the point of interest (POI = marker). Use for static receivers only.
    • The parameters delta_e, delta_n and delta_u are the offsets in the East, North and Up (ENU) directions respectively, expressed in meters.
    • All absolute positions reported by the receiver are POI positions, obtained by subtracting this offset from the ARP. The purpose is to take into account the fact that the antenna may not be located directly on the surveying POI.
    • default: 0.0, 0.0 and 0.0

Antenna Attitude Offset

+ `att_offset`: Angular offset between two antennas (Main and Aux) and vehicle frame
+ `heading`: The perpendicular (azimuth) axis can be compensated for by adjusting the `heading` parameter
+ `pitch`: Vertical (elevation) offset can be compensated for by adjusting the `pitch` parameter
+ default: `0.0`, `0.0` (degrees)

Antenna Specs

  • ant_type: type of your main GNSS antenna
    • For best positional accuracy, it is recommended to select a type from the list returned by the command lstAntennaInfo, Overview. This is the list of antennas for which the receiver can compensate for phase center variation.
    • By default and if ant_type does not match any entry in the list returned by lstAntennaInfo, Overview, the receiver will assume that the phase center variation is zero at all elevations and frequency bands, and the position will not be as accurate.
    • default: Unknown
  • ant_serial_nr: serial number of your main GNSS antenna
  • ant_aux1_type and ant_aux1_serial_nr: same for Aux1 antenna

Leap Seconds

  • leap_seconds: Leap seconds are automatically gathered from the receiver via the SBF block ReceiverTime. If a log file is used for simulation and this block was not recorded, the number of leap seconds that have been inserted up until the point of ROSaic usage can be set by this parameter.
    • At the time of writing the code (2020), the GPS time, which is unaffected by leap seconds, was ahead of UTC time by 18 leap seconds. Adapt the leap_seconds parameter accordingly as soon as the next leap second is inserted into the UTC time or in case you are using ROSaic for the purpose of simulations.

Polling Periods

  • polling_period/pvt: desired period in milliseconds between the polling of two consecutive PVTGeodetic, PosCovGeodetic, PVTCartesian and PosCovCartesian blocks and - if published - between the publishing of two of the corresponding ROS messages (e.g. septentrio_gnss_driver/PVTGeodetic.msg). Consult firmware manual for allowed periods. If the period is set to a lower value than the receiver is capable of, it will be published with the next higher period. If set to 0, the SBF blocks are output at their natural renewal rate (OnChange).
  • polling_period/rest: desired period in milliseconds between the polling of all other SBF blocks and NMEA sentences not addressed by the previous parameter, and - if published - between the publishing of all other ROS messages
    • default: 500 (2 Hz)

Time Systems

  • use_gnss_time: true if the ROS message headers' unix epoch time field shall be constructed from the TOW/WNC (in the SBF case) and UTC (in the NMEA case) data, false if those times shall be taken by the driver from ROS time. If use_gnss_time is set to true, make sure the ROS system is synchronized to an NTP time server either via internet or ideally via the Septentrio receiver since the latter serves as a Stratum 1 time server not dependent on an internet connection. The NTP server of the receiver is automatically activated on the Septentrio receiver (for INS/GNSS a firmware >= 1.3.3 is needed).
    • default: true
  • latency_compensation: Rx reports processing latency in PVT and INS blocks. If set to truethis latency is subtracted from ROS timestamps in related blocks (i.e., use_gnss_time set to false). Related blocks are INS, PVT, Covariances, and BaseVectors. In case of use_gnss_time set to true, the latency is already compensated within the RX and included in the reported timestamps.
    • default: false

RTK corrections

  • rtk_settings: determines RTK connection parameters
    • There are multiple possibilities to feed RTK corrections to the Rx. They may be set simultaneously and the Rx will choose the nearest source.
      • a) ntrip_# if the Rx has internet access and is able to receieve NTRIP streams from a caster. Up to three NTRIP connections are possible.
      • b) ip_server_# if corrections are to be receieved via TCP/IP for example over Data Link from Septentrio's RxTools is installed on a computer. Up to five IP server connections are possible.
      • c) serial_# if corrections are to be receieved via a serial port for example over radio link from a local RTK base or over Data Link from Septentrio's RxTools installed on a computer. Up to five serial connections are possible.
    • ntrip_#: for receiving corretions from an NTRIP caster (# is from 1 ... 3).
      • id: NTRIP connection NTR1, NTR2, or NTR3.
      • default: ""
      • caster: is the hostname or IP address of the NTRIP caster to connect to.
      • default: ""
      • caster_port: IP port of the NTRIP caster.
      • default: 2021
      • username: user name for the NTRIP caster.
      • default: ""
      • pasword: password for the NTRIP caster. The receiver encrypts the password so that it cannot be read back with the command "getNtripSettings".
      • default: ""
      • mountpoint: mount point of the NTRP caster to be used.
      • default: ""
      • version: argument specifies which version of the NTRIP protocol to use (v1 or v2).
      • default: "v2"
      • tls: determines wether to use TLS.
      • default: false
      • fingerprint: fingerprint to be used if the certificate is self-signed. If the caster’s certificate is known by a publicly-trusted certification authority, fingerprint should be left empty.
      • default: ""
      • rtk_standard: determines the RTK standard, options are auto, RTCMv2, RTCMv3, or CMRv2.
      • default: "auto"
      • send_gga: specifies whether or not to send NMEA GGA messages to the NTRIP caster, and at which rate. It must be one of auto, off, sec1, sec5, sec10 or sec60. In auto mode, the receiver automatically sends GGA messages if requested by the caster.
      • default: "auto"
      • keep_open: determines wether this connection shall be kept open. If set to true the Rx will still be able to receive RTK corrections to improve precision after driver is shut down.
      • default: true
    • ip_server_#: for receiving corretions via TCP/IP (# is from 1 ... 5).
      • id: specifies the IP server IPS1, IPS2, IPS3, IPS4, or IPS5. Note that ROSaic will send GGA messages on this connection if send_gga is set, such that in the Data Link application of RxTools one just needs to set up a TCP client to the host name as found in the ROSaic parameter device with the port as found in port. If the latter connection were connection 1 on Data Link, then connection 2 would set up an NTRIP client connecting to the NTRIP caster as specified in the above parameters in order to forward the corrections from connection 2 to connection 1.
      • default: ""
      • port: its port number of the connection that ROSaic establishes on the receiver. When selecting a port number, make sure to avoid conflicts with other services.
      • default: 0
      • rtk_standard: determines the RTK standard, options are auto, RTCMv2, RTCMv3, or CMRv2.
      • default: ""
      • send_gga: specifies whether or not to send NMEA GGA messages to the NTRIP caster, and at which rate. It must be one of auto, off, sec1, sec5, sec10 or sec60. In auto mode, the receiver sends with sec1.
      • default: "auto"
      • keep_open: determines wether this connection shall be kept open. If set to true the Rx will still be able to receive RTK corrections to improve precision after driver is shut down.
      • default: true
    • serial_#: for receiving corretions via serial connection (# is from 1 ... 5).
      • port: Serial connection COM1, COM2, COM3, USB1, or USB2 on which corrections could be forwarded to the Rx from a serially connected radio link modem or via Data Link for example.
      • default: ""
      • baud_rate: sets the baud rate of this port for genuine serial ports, i.e., not relevant for USB connection.
      • default: 115200
      • rtk_standard: determines the RTK standard, options are auto, RTCMv2, RTCMv3, or CMRv2.
      • default: "auto"
      • send_gga: specifies whether or not to send NMEA GGA messages to the NTRIP caster, and at which rate. It must be one of auto, off, sec1, sec5, sec10 or sec60. In auto mode, the receiver sends with sec1.
      • default: "auto"
      • keep_open: determines wether this connection shall be kept open. If set to true the Rx will still be able to receive RTK corrections to improve precision after driver is shut down.
      • default: true

INS Specs

+ `ins_spatial_config`: Spatial configuration of INS/IMU. Coordinates according to vehicle related frame directions chosen by `use_ros_axis_orientation` (front-left-up if `true` and front-right-down if `false`).
  + `imu_orientation`: IMU sensor orientation
    + Parameters `theta_x`, `theta_y` and `theta_z` are used to determine the sensor orientation with respect to the vehicle frame. Positive angles correspond to a right-handed (clockwise) rotation of the IMU with respect to its nominal orientation (see below). The order of the rotations is as follows: `theta_z` first, then `theta_y`, then `theta_x`.
    + The nominal orientation is where the IMU is upside down and with the `X axis` marked on the receiver pointing to the front of the vehicle. By contrast, for `use_ros_axis_orientation: true`, nominal orientation is where the `Z axis` of the IMU is pointing upwards and also with the `X axis` marked on the receiver pointing to the front of the vehicle.
    + default: `0.0`, `0.0`, `0.0` (degrees)
  + `poi_lever_arm`: The lever arm from the IMU reference point to a user-defined POI
    + Parameters `delta_x`,`delta_y` and `delta_z` refer to the vehicle reference frame
    + default: `0.0`, `0.0`, `0.0` (meters)
  + `ant_lever_arm`: The lever arm from the IMU reference point to the main GNSS antenna
    + The parameters `x`,`y` and `z` refer to the vehicle reference frame
    + default: `0.0`, `0.0`, `0.0` (meters)
  + `vsm_lever_arm`: The lever arm from the IMU reference point to the velocity sensor
    + The parameters `vsm_x`,`vsm_y` and `vsm_z` refer to the vehicle reference frame 
    + default: `0.0`, `0.0`, `0.0` (meters)
+ `ins_initial_heading`: How the receiver obtains the initial INS/GNSS integrated heading during the alignment phase
    + In case it is `auto`, the initial integrated heading is determined from GNSS measurements.
    + In case it is `stored`, the last known heading when the vehicle stopped before switching off the receiver is used as initial heading. Use if vehicle does not move when the receiver is switched off.
    + default: `auto`
+ `ins_std_dev_mask`: Maximum accepted error
  + `att_std_dev`: Configures an output limit on standard deviation of the attitude angles (max error accepted: 5 degrees)
  + `pos_std_dev`: Configures an output limit on standard deviation of the position (max error accepted: 100 meters)
  + default: `5` degrees, `10` meters    
+ `ins_use_poi`: Whether or not to use the POI defined in `ins_spatial_config/poi_lever_arm`
  + If true, the point at which the INS navigation solution (e.g. in `insnavgeod` ROS topic) is calculated will be the POI as defined above (`poi_frame_id`), otherwise it'll be the main GNSS antenna (`frame_id`). Has to be set to `true` if tf shall be published.
  + default: `true`
+ `ins_vsm`: Configuration of the velocity sensor measurements.
  + `ros`: VSM info received from ROS msgs
    + `source`: Specifies which ROS message type shall be used, options are `odometry`or `twist`. Accordingly, a subscriber is established of the type [`nav_msgs/Odometry.msg`](https://docs.ros.org/en/api/nav_msgs/html/msg/Odometry.html) or [`geometry_msgs/TwistWithCovarianceStamped.msg`](https://docs.ros.org/en/api/sensor_msgs/html/msg/TwistWithCovarianceStamped.html) listening on the topics `odometry_vsm` or `twist_vsm` respectively. Only linear velocities are evaluated. Measurements have to be with respect to the frame aligned with the vehicle and defined by `ins_spatial_config.vsm_lever_arm` or tf-frame `vsm_frame_id`, see also comment in [`nav_msgs/Odometry.msg`](https://docs.ros.org/en/api/nav_msgs/html/msg/Odometry.html) that twist should be specified in `child_frame_id`.
      + default: ""
    + `config`: Defines which measurements belonging to the respective axes are forwarded to the INS. In addition, non-holonomic constraints may be introduced for directions known to be restricted in movement. For example, a vehicle with Ackermann steering is limited in its sidewards and upwards movement. So, even if only motion in x-direction may be measured, zero-velocities for y and z may be sent.
      + default: []
    + `variances_by_parameter`: Wether variances shall be entered by parameter `ins_vsm/ros/variances` or the values from inside the ROS messages are used.
      + default: false
    + `variances`: Variances of the respective axes. Only have to be set if `ins_vsm/ros/variances_by_parameter` is set to `true`. Values must be > 0.0, else measurements cannot not be used. 
      + default: []
  + `ip_server`:
    + `id`: IP server to receive the VSM info (e.g. `IPS2`).
        + default: ""
    + `port`: TCP port to receive the VSM info. When selecting a port number, make sure to avoid conflicts with other services.
      + default: 0
    + `keep_open` determines wether this connections to receive VSM shall be kept open on driver shutdown. If set to `true` the Rx will still be able to use external VSM info to improve its localization.
      + default: `true`
  + `serial`:
    + `port`: Serial port to receive the VSM info.
      + default: ""
    + `baud_rate`: Baud rate of the serial port to receive the VSM info.
      + default: 115200
    + `keep_open` determines wether this connections to receive VSM shall be kept open on driver shutdown. If set to `true` the Rx will still be able to use external VSM info to improve its localization.
      + default: `true`

Logger

+ `activate_debug_log`: `true` if ROS logger level shall be set to debug.

  • Parameters Configuring Publishing of ROS Messages

    NMEA/SBF Messages to be Published

    • publish/gpgga: true to publish nmea_msgs/GPGGA.msg messages into the topic /gpgga
    • publish/gprmc: true to publish nmea_msgs/GPRMC.msg messages into the topic /gprmc
    • publish/gpgsa: true to publish nmea_msgs/GPGSA.msg messages into the topic /gpgsa
    • publish/gpgsv: true to publish nmea_msgs/GPGSV.msg messages into the topic /gpgsv
    • publish/measepoch: true to publish septentrio_gnss_driver/MeasEpoch.msg messages into the topic /measepoch
    • publish/galauthstatus: true to publish septentrio_gnss_driver/GALAuthStatus.msg messages into the topic /galauthstatus and corresponding /diganostics
    • publish/aimplusstatus: true to publish septentrio_gnss_driver/RFStatus.msg messages into the topic /rfstatus, septentrio_gnss_driver/AIMPlusStatus.msg messages into /aimplusstatus and corresponding /diganostics. Some information is only available with active OSNMA.
    • publish/pvtcartesian: true to publish septentrio_gnss_driver/PVTCartesian.msg messages into the topic /pvtcartesian
    • publish/pvtgeodetic: true to publish septentrio_gnss_driver/PVTGeodetic.msg messages into the topic /pvtgeodetic
    • publish/basevectorcart: true to publish septentrio_gnss_driver/BaseVectorCart.msg messages into the topic /basevectorcart
    • publish/basevectorgeod: true to publish septentrio_gnss_driver/BaseVectorGeod.msg messages into the topic /basevectorgeod
    • publish/poscovcartesian: true to publish septentrio_gnss_driver/PosCovCartesian.msg messages into the topic /poscovcartesian
    • publish/poscovgeodetic: true to publish septentrio_gnss_driver/PosCovGeodetic.msg messages into the topic /poscovgeodetic
    • publish/velcovcartesian: true to publish septentrio_gnss_driver/VelCovCartesian.msg messages into the topic /velcovcartesian
    • publish/velcovgeodetic: true to publish septentrio_gnss_driver/VelCovGeodetic.msg messages into the topic /velcovgeodetic
    • publish/atteuler: true to publish septentrio_gnss_driver/AttEuler.msg messages into the topic /atteuler
    • publish/attcoveuler: true to publish septentrio_gnss_driver/AttCovEuler.msg messages into the topic /attcoveuler
    • publish/gpst: true to publish sensor_msgs/TimeReference.msg messages into the topic /gpst
    • publish/navsatfix: true to publish sensor_msgs/NavSatFix.msg messages into the topic /navsatfix
    • publish/gpsfix: true to publish gps_common/GPSFix.msg messages into the topic /gpsfix
    • publish/pose: true to publish geometry_msgs/PoseWithCovarianceStamped.msg messages into the topic /pose
    • publish/twist: true to publish geometry_msgs/TwistWithCovarianceStamped.msg messages into the topics /twist and /twist_ins respectively
    • publish/diagnostics: true to publish diagnostic_msgs/DiagnosticArray.msg messages into the topic /diagnostics
    • publish/insnavcart: true to publish septentrio_gnss_driver/INSNavCart.msg message into the topic/insnavcart
    • publish/insnavgeod: true to publish septentrio_gnss_driver/INSNavGeod.msg message into the topic/insnavgeod
    • publish/extsensormeas: true to publish septentrio_gnss_driver/ExtSensorMeas.msg message into the topic/extsensormeas
    • publish/imusetup: true to publish septentrio_gnss_driver/IMUSetup.msg message into the topic/imusetup
    • publish/velsensorsetup: true to publish septentrio_gnss_driver/VelSensorSetup.msgs message into the topic/velsensorsetup
    • publish/exteventinsnavcart: true to publish septentrio_gnss_driver/ExtEventINSNavCart.msgs message into the topic/exteventinsnavcart
    • publish/exteventinsnavgeod: true to publish septentrio_gnss_driver/ExtEventINSNavGeod.msgs message into the topic/exteventinsnavgeod
    • publish/imu: true to publish sensor_msgs/Imu.msg message into the topic/imu
    • publish/localization: true to publish nav_msgs/Odometry.msg message into the topic/localization
    • publish/tf: true to broadcast tf of localization. ins_use_poi must also be set to true to publish tf. Note that only one of publish/tf or publish/tf_ecef may be true.
    • publish/localization_ecef: true to publish nav_msgs/Odometry.msg message into the topic/localization related to ECEF frame.
    • publish/tf_ecef: true to broadcast tf of localization related to ECEF frame. ins_use_poi must also be set to true to publish tf. Note that only one of publish/tf or publish/tf_ecef may be true.

ROS Topic Publications

A selection of NMEA sentences, the majority being standardized sentences, and proprietary SBF blocks is translated into ROS messages, partly generic and partly custom, and can be published at the discretion of the user into the following ROS topics. All published ROS messages, even custom ones, start with a ROS generic header std_msgs/Header.msg, which includes the receiver time stamp as well as the frame ID, the latter being specified in the ROS parameter frame_id.

Available ROS Topics

  • /gpgga: publishes nmea_msgs/Gpgga.msg - converted from the NMEA sentence GGA.
  • /gprmc: publishes nmea_msgs/Gprmc.msg - converted from the NMEA sentence RMC.
  • /gpgsa: publishes nmea_msgs/Gpgsa.msg - converted from the NMEA sentence GSA.
  • /gpgsv: publishes nmea_msgs/Gpgsv.msg - converted from the NMEA sentence GSV.
  • /measepoch: publishes custom ROS message septentrio_gnss_driver/MeasEpoch.msg, corresponding to the SBF block MeasEpoch.
  • /galauthstatus: publishes custom ROS message septentrio_gnss_driver/GALAuthStatus.msg, corresponding to the SBF block GALAuthStatus.
  • /rfstatus: publishes custom ROS message septentrio_gnss_driver/RFStatus.msg, compiled from the SBF block RFStatus.
  • /aimplusstatus: publishes custom ROS message septentrio_gnss_driver/AIMPlusStatus.msg, reporting status of AIM+. Converted from SBF blocks RFStatus and optionally GALAuthStatus. For the latter OSNMA has to be activated.
  • /pvtcartesian: publishes custom ROS message septentrio_gnss_driver/PVTCartesian.msg, corresponding to the SBF block PVTCartesian (GNSS case) or INSNavGeod (INS case).
  • /pvtgeodetic: publishes custom ROS message septentrio_gnss_driver/PVTGeodetic.msg, corresponding to the SBF block PVTGeodetic (GNSS case) or INSNavGeod (INS case).
  • /basevectorcart: publishes custom ROS message septentrio_gnss_driver/BaseVectorCart.msg, corresponding to the SBF block BaseVectorCart.
  • /basevectorgeod: publishes custom ROS message septentrio_gnss_driver/BaseVectorGeod.msg, corresponding to the SBF block BaseVectorGeod.
  • /poscovcartesian: publishes custom ROS message septentrio_gnss_driver/PosCovCartesian.msg, corresponding to SBF block PosCovCartesian (GNSS case) or INSNavGeod (INS case).
  • /poscovgeodetic: publishes custom ROS message septentrio_gnss_driver/PosCovGeodetic.msg, corresponding to SBF block PosCovGeodetic (GNSS case) or INSNavGeod (INS case).
  • /velcovcartesian: publishes custom ROS message septentrio_gnss_driver/VelCovCartesian.msg, corresponding to SBF block VelCovCartesian (GNSS case).
  • /velcovgeodetic: publishes custom ROS message septentrio_gnss_driver/VelCovGeodetic.msg, corresponding to SBF block VelCovGeodetic (GNSS case).
  • /atteuler: publishes custom ROS message septentrio_gnss_driver/AttEuler.msg, corresponding to SBF block AttEuler.
  • /attcoveuler: publishes custom ROS message septentrio_gnss_driver/AttCovEuler.msg, corresponding to the SBF block AttCovEuler.
  • /gpst (for GPS Time): publishes generic ROS message sensor_msgs/TimeReference.msg, converted from the PVTGeodetic (GNSS case) or INSNavGeod (INS case) block's GPS time information, stored in its block header.
  • /navsatfix: publishes generic ROS message sensor_msgs/NavSatFix.msg, converted from the SBF blocks PVTGeodetic,PosCovGeodetic (GNSS case) or INSNavGeod (INS case).
  • /gpsfix: publishes generic ROS message gps_msgs/GPSFix.msg, which is much more detailed than sensor_msgs/NavSatFix.msg, converted from the SBF blocks PVTGeodetic, PosCovGeodetic, ChannelStatus, MeasEpoch, AttEuler, AttCovEuler, VelCovGeodetic, DOP (GNSS case) or INSNavGeod, DOP (INS case). In order to publish heading information, the field dip is diverted from its intended meaning an populated with the heading angle and err_dip with its uncertainty.
  • /pose: publishes generic ROS message geometry_msgs/PoseWithCovarianceStamped.msg, converted from the SBF blocks PVTGeodetic, PosCovGeodetic, AttEuler, AttCovEuler (GNSS case) or INSNavGeod (INS case).
    • Note that GNSS provides absolute positioning, while robots are often localized within a local level cartesian frame. The pose field of this ROS message contains position with respect to the absolute ENU frame (longitude, latitude, height), i.e. not a cartesian frame, while the orientation is with respect to a vehicle-fixed (e.g. for mosaic-x5 in moving base mode via the command setAttitudeOffset, ...) !local! NED frame or ENU frame if use_ros_axis_directions is set true. Thus the orientation is !not! given with respect to the same frame as the position is given in. The cross-covariances are hence set to 0.
  • /twist: publishes generic ROS message geometry_msgs/TwistWithCovarianceStamped.msg, converted from the SBF blocks PVTGeodetic and VelCovGeodetic.
  • /twist_ins: publishes generic ROS message geometry_msgs/TwistWithCovarianceStamped.msg, converted from SBF block INSNavGeod.
  • /insnavcart: publishes custom ROS message septentrio_gnss_driver/INSNavCart.msg, corresponding to SBF block INSNavCart.
  • /insnavgeod: publishes custom ROS message septentrio_gnss_driver/INSNavGeod.msg, corresponding to SBF block INSNavGeod.
  • /extsensormeas: publishes custom ROS message septentrio_gnss_driver/ExtSensorMeas.msg, corresponding to SBF block ExtSensorMeas.
  • /imusetup: publishes custom ROS message septentrio_gnss_driver/IMUSetup.msg, corresponding to SBF block IMUSetup.
  • /velsensorsetup: publishes custom ROS message septentrio_gnss_driver/VelSensorSetup.msg corresponding to SBF block VelSensorSetup.
  • /exteventinsnavcart: publishes custom ROS message septentrio_gnss_driver/INSNavCart.msg, corresponding to SBF block ExtEventINSNavCart.
  • /exteventinsnavgeod: publishes custom ROS message septentrio_gnss_driver/INSNavGeod.msg, corresponding to SBF block ExtEventINSNavGeod.
  • /diagnostics: accepts generic ROS message diagnostic_msgs/DiagnosticArray.msg, converted from the SBF blocks QualityInd, ReceiverStatus and ReceiverSetup.
  • /imu: accepts generic ROS message sensor_msgs/Imu.msg, converted from the SBF blocks ExtSensorMeas and INSNavGeod.
    • The ROS message sensor_msgs/Imu.msg can be fed directly into the robot_localization of the ROS navigation stack. Note that use_ros_axis_orientation should be set to true to adhere to the ENU convention.
  • /localization: accepts generic ROS message nav_msgs/Odometry.msg, converted from the SBF block INSNavGeod and transformed to UTM.
    • The ROS message nav_msgs/Odometry.msg can be fed directly into the robot_localization of the ROS navigation stack. Note that use_ros_axis_orientation should be set to true to adhere to the ENU convention.
  • /localization_ecef: accepts generic ROS message nav_msgs/Odometry.msg, converted from the SBF blocks INSNavCart and INSNavGeod.
    • The ROS message nav_msgs/Odometry.msg can be fed directly into the robot_localization of the ROS navigation stack. Note that use_ros_axis_orientation should be set to true to adhere to the ENU convention.

Suggestions for Improvements

Some Ideas + Equip ROSaic with an NTRIP client such that it can forward corrections to the receiver independently of `Data Link`.

Adding New SBF Blocks or NMEA Sentences

Steps to Follow Is there an SBF or NMEA message that is not being addressed while being important to your application? If yes, follow these steps: 1. Find the log reference of interest in the publicly accessible, official documentation. Hence select the reference guide file, e.g. for mosaic-x5 in the [product support section for mosaic-X5](https://www.septentrio.com/en/support/mosaic/mosaic-x5), Chapter 4, of Septentrio's homepage. 2. SBF: Add a new `.msg` file to the `../msg` folder. And modify the `../CMakeLists.txt` file by adding a new entry to the `add_message_files` section. 3. Add msg header and typedef to `typedefs.hpp`. 4. Parsers: - SBF: Add a parser to the `sbf_blocks.hpp` file. - NMEA: Construct two new parsing files such as `gpgga.cpp` to the `../src/septentrio_gnss_driver/parsers/nmea_parsers` folder and one such as `gpgga.hpp` to the `../include/septentrio_gnss_driver/parsers/nmea_parsers` folder. 5. Processing the message/block: - SBF: Extend the `SbfId` enumeration in the `message_handler.hpp` file with a new entry. - SBF: Extend the SBF switch-case in `message_handler.cpp` file with a new case. - NMEA: Extend the `nmeaMap_` in the `message_handler.hpp` file with a new pair. - NMEA: Extend the NMEA switch-case in `message_handler.cpp` file with a new case. 6. Create a new `publish/..` ROSaic parameter in the `../config/rover.yaml` file and create a boolean variable `publish_xxx` in the struct in the `settings.h` file. Parse the parameter in the `rosaic_node.cpp` file. 7. Add SBF block or NMEA to data stream setup in `communication_core.cpp` (function `configureRx()`).
CHANGELOG

Changelog for package septentrio_gnss_driver

1.3.2 (2023-11-19)

  • Commits

    : - Merge pull request #97 from thomasemter/dev/next Integrate README changes from master - Fix topics namespace - Fix units of imu angular rates - Merge upstream README pt2 - Merge upstream README - Update README.md - Update README.md - Update README.md - v1.3.1 - Updated package.xml - v1.3.1 - Updated package.xml - v1.3.1 - Updated package.xml - v1.3.1 - Updated changelog - Merge pull request #95 from thomasemter/dev/next Fix navsatfix and gpsfix frame ids - Update README.md - Fix navsatfix and gpsfix frame ids - Merge pull request #92 from thomasemter/dev/next Fix single antenna receiver setup - Update changelog - Merge - Fix single antenna receiver setup - Merge pull request #90 from thomasemter/dev/next Fix empty headers - Merge branch \'dev\' into dev/next - Bump version - Fix empty headers - Merge pull request #88 from thomasemter/dev/next Fix navsatfix containing only zeros for INS - Align indent - Fix navsatfix containig only zeros for INS - Merge pull request #87 from thomasemter/dev/next Update firmware info - Reduce INS firmware version info to released version - Update firmware info - v1.3.0 - Updated package.xml - v1.3.0 - Update firmware info - Updated package.xml - v1.3.0 - Merge pull request #84 from thomasemter/dev/next Update readme - Add expected release dates - Add known issues to readme - Update version - Update readme - Merge pull request #81 from thomasemter/dev/next Fix spelling - Improve explanations in readme - Categorize stream params - Add keep alive check for TCP - Fix spelling - Change angle wrapping - Add TCP communication via static IP server - Add units to msgs - Fix spelling - Merge pull request #75 from thomasemter/dev/next upcoming release - Add heading to GPSFix msg - Move constant - Change log level of firmware check - Add improved VSM handling - Change INS in GNSS node detection to auto - Fix invald v_x var case - Refine readme on UDP - Improve server duplicate check - Add more info un UDP configuration - Fix publish check - Add more publishing checks for configured Rx - Add const for max udp packet size - Update readme and changelog - Add device check to node - Add checks for IP server duplicates - Add latency compensation to att msgs - Add device check logic - Add UDP params and setup logic - Fix multi msg per packet - Fix localization stamp and tf publishing - Change VSM to be averaged and published with 2 Hz - Always publish raw IMU data as indicated - Change to empty fields - Refine diagnostics naming scheme and add trigger to ensure emission of ReceiverSetup - Change diagnostics naming scheme - Expand readme on AIM+ - Reformulate readme about ROS and ROS2 - Rename msg var - Add custom message to report AIM+ status - Catch invalid UTM conversion - Robustify command reset - Add RFStatus diagnostics - Merge branch \'dev/next\' of https://github.com/thomasemter/septentrio_gnss_driver into dev/next - Add VelCovCartesian output - Add VelCovCartesian output - Refine Rx type check - Ensure latency reporting block is activated - Add option for latency compensation - Fix param type misinterpretation - Add missing param to example in readme - Add OSNMA diagnostics output - Add keep_open option to OSNMA - Add OSNMA msg - Update changelog - Refine README and fix compiled message logic - Update changelog - Add warning for configuring INS as GNSS - Add warn log for misconfiguration - Fix pose publishing rate - Fix navsatfix publishing - Make vars const - Replace log functions - Add small fixes and cleanup - Merge branch \'dev/next\' of https://github.com/thomasemter/septentrio_gnss_driver into dev/next - Add option to bypass configuration of Rx - Add option to bypass confugration of Rx - Add diagnostics and time ref msgs again - Update README on how to add new messages - Add automiatic detection of serial port ID - Refine changelog - Change invalid timestamp handling for reading from file - Add USB serial by ID info to README - Fix leap seconds for timestamp if reading from file - Fix reconnection logic - Replace flow control setup - Refactor ioservice - notify semaphores in destructor - Send port reset only once - Fix serial connection - Fix talker ID setting for INS - Add NMEA talker ID setting to ensure reception - Prepare communication for UDP option (still inactive) - Fix UDP message identification logic - Add test code for UDP, WIP - Add UDP client, WIP - Set do-not-use for temp to NaN - Add processing latency correction for ROS timestamps - Fix extsensor parser - Add units to remaining msgs - Add nodiscard attribute to functions - Add nodiscard attribute to functions - Add nodiscard attribute to functions - Add const specifiers to functions - Make settings access const - Move SBF ID handling - Refactor header assembly - Rename message handler again - Change parsing utilities and crc to get message - Add namespace to enum - Change timestamp code - Update changelog - Change class privacy - Add assembled messages, to be tested - Add units to come msg definitions - Add custom BlockHeader constructor - Move wait - Remove copy paste vars - Add file readers - Fix reset main connection on exit hang - Fix handling of INS NMEA talker ID - Fix error response detection - Add packing of generic string messages - Exchange concurrent queue - Remove obsolete includes - Add NMEA handling - Change syncronization to semaphore - Add message parser, WIP - Rearrange io handling, WIP - Refactor and cleanup - Improve io handling, WIP - Refactor message parser, WIP - Add message handler - Add io modules - Add new low level interface, WIP - Change connection thread - Fix attitude cov flipped twice - Add cov alignment from true north to grid north - Rename meridian convergence and fix sense - Remove obsolete define - Fix spelling errors - Merge branch \'master\' into dev/next - v1.2.3 - Update package.xml - v1.2.3 - Update package.xml - v1.2.3 - Update package.xml - v1.2.3 - Update package.xml - Merge pull request #68 from thomasemter/master dev - Fix lat/long in rad - Reorder localization msg filling - Update readme - Fix NED to ECEF rotation matrix - Add localization ECEF publishing - Merge branch \'dev/next\' of https://github.com/thomasemter/septentrio_gnss_driver into dev/next - Merge branch \'dev/next\' of https://github.com/thomasemter/septentrio_gnss_driver into dev/next - Merge branch \'dev/next\' of https://github.com/thomasemter/septentrio_gnss_driver into dev/next - Add ecef localization msg - Add local to ecef transforms - Change default datum to Default - Clean up block data size defines - Change default datum to WGS84 - Set correct value for max number of base vector info - Add check on shutdown to only close ports on hardware - Refine readme - Merge branch \'master\' of https://github.com/thomasemter/septentrio_gnss_driver - Add missing param - Add possibility to use multiple RTK corrections of the same type - Only set baud rates on real serial ports - Fix decimal places trimming - Update changelog - Merge branch \'dev/next\' - Add base vecotr info to README - Change param to empty vector - Change param to empty vector - Fix template argument - Add quotation marks to pw if it contains spaces - Add quotation marks to pw if it contains spaces - Add option to keep aiding connections open on shutdown - Merge branch \'master\' into dev/next - Add option to keep aiding connections open on shutdown - Disable ntrip on shutdown - Disable ntrip on shutdown - Add base vector callbacks and publishing, WIP - Add base vector msgs and parsers, WIP - Fix comment swap - Add send_gga option to serial RTK and fix IP server id - Add possibility to specify IP server connection - Increase version number in package.xml and harmonize it with ROS2 - Reset main port to auto input - Add reset all used ports on shutdown - Improve readme - Change vsm options to allow simultaneous input - Change corrections settings to receiver simultaneously - Change correction options to be used simultenously - Change param name for future extensibility - Change param name for future extensibility - Rework corretion parameters and add more flexible options - Fix some spelling in readme - Add receiver type INS as GNSS - Add option to use external VSM input - Add more log output for vsm - Add VSM from odometry or twist ROS messages - Fix GPGGA and GPRMC timestamp from GNSS - Use only one stream for NMEA messages - Fix merge error - Fix merge error - Add all possible periods and rework validity check - Update changelog - Add 5 ms period option - Fix changelog - Add twist output - Add missing files to clang-formatting - Merge branch \'dev/next\' - Merge branch \'master\' of https://github.com/thomasemter/septentrio_gnss_driver - Format according to clang-format - Change log level of local frame tf insertion - Always register ReceiverSetup - Add firmware checks - Add log and info to README - Add insertion of local frame - Update README and CHANGELOG - Use leap seconds from receiver - Update changelog - Add config files for GNSS and INS - Add ReceiverTime, WIP - Add configs for GNSS and INS - Contributors: Thomas Emter, Tibor Dome, septentrio-users, tibordome

1.3.1 (2023-07-06)

  • New Features

    : - Recovery from connection interruption - Add option to bypass configuration of Rx - OSNMA - Latency compensation for ROS timestamps - Output of SBF block VelCovCartesian - Support for UDP and TCP via IP server - New VSM handling allows for unknown variances (INS firmware >= 1.4.1) - Add heading angle to GPSFix msg (by diverting dip field, cf. readme)

  • Improvements

    : - Rework IO core and message handling - Unified stream processing - Internal data queue - Prevent message loss in file reading - Add some explanatory warnings for parameter mismatches - Add units to message definitions

  • Fixes

    : - navsatfix for INS - Empty headers - Single antenna receiver setup

  • Preliminary Features

    : - Output of localization and tf in ECEF frame, testing and feedback welcome

1.2.3 (2022-11-09)

  • New Features

    : - Twist output option - Example config files for GNSS and INS - Get leap seconds from receiver - Firmware check - VSM from odometry or twist ROS messages - Add receiver type in case INS is used in GNSS mode - Add publishing of base vector topics

  • Improvements

    : - Rework RTK corrections parameters and improve flexibility

  • Fixes

    : - /tf not being published without /localization - Twist covariance matrix of localization - Support 5 ms period for IMU explicitly

1.1.2 (2022-06-22)

  • Fixes

    : - Memory corruption under adverse conditions

1.1.1 (2022-05-16)

  • New Features

    : - Add login credentials - Activate NTP server if use_gnss_time is set to true

  • Improvements

    : - Add NED option to localization

  • Fixes

    : - IMU orientation for ROS axis convention

  • Commits

    : - Merge pull request #62 from thomasemter/dev/next Small fixes and additions - Amend readme regarding robot_localization - Add more explanations for IMU orientation in ROS convention - Fix formatting in readme - Fix package name in readme - Update readme - Update changelog - Fix IMU orientation for ROS axis orientation - Activate NTP only if GNSS time is used - Add NED option to localization - Set NMEA header to - Fix logging causing crash - Update readme and changelog - Activate NTP server - Add credentials for access control - Contributors: Thomas Emter, Tibor Dome

1.1.0 (2022-04-25)

  • New Features

    : - Add option to use ROS axis orientations according to REP103 - Add frame_id parameters - Add option to get frames from tf - Publishing of cartesian localization in UTM (topic and/or tf) for INS - Publishing of IMU topic for INS - Publishing of MeasEpoch - ROS2 branch

  • Improvements

    : - Add multi antenna option - Increase number of SBF streams - Add option to set polling_period to \"on change\" - Increased buffer size from 8192 to 131072 bytes - Add endianess aware parsers - Only publish topics set to true - Add parameter to switch DEBUG logging on and off - Change GPxxx messages to ROS built-in types - Remove duplicate INS msg types

  • Fixes

    : - Setting of antenna type - Publishing rate interconnections of gpsfix and velcovgeodetic - Missing quotes for antenna type - Broken attitude parsing pose and gpsfix from INS - IMU orientation was not sent to Rx - Graceful shutdown of threads

  • Commits

    : - Merge branch \'dev\' - Prepare new release - Prepare new release - Merge pull request #53 from thomasemter/dev/refactor Very last changes - Add geographic lib dependency to package.xml - Add comment for frame of main antenna - Move utm zone locking section in readme - Reformulate readme section on frames - Merge pull request #52 from thomasemter/dev/refactor Last changes - Change frame id back to poi_frame_id - Make error log more explicit - Merge pull request #49 from thomasemter/dev/refactor Improve IMU blocks sync and do-not-use value handling - Fix buffer size in changelog - Turn off Nagle\'s algorithm for TCP - Fix changelog formatting - Fix readme - Set default base frame to base_link - Fix valid tow check logic - Increase buffer size for extreme stress tests - Fix crc check - Fix and streamline tf handling - Add checks for validity of values - Fix rad vs deg - Update changelog - Add some comments - Set stdDevMask to values > 0.0 in node - Set stdDevMask to values > 0.0 - Add info on RNDIS and set it to default - Increase default serial baud rate - Add parameter to set log level to debug - Change defaults for publishers in node - Put publish params together and fix mismatch in readme - Improve IMU blocks sync and do-not-use value handling - Merge pull request #48 from thomasemter/dev/refactor Fix measepoch not publishing without gpsfix - Fix measepoch not publishing without gpsfix - Merge pull request #47 from thomasemter/dev/refactor Dev/refactor - Publish only messages set to true - Remove leftover declaration - Merge branch \'dev/endianess_agnostic\' into dev/refactor - Update readme to reflect endianess aware parsing - Remove msg smart pointers - Fix array assertion failure - Cleanup - Add ReceiverStatus parser - Add QualityInd parser - Add DOP parser - Add ReceiverSetup parser - Fix MeasEpoch and ChannelStatus parsers, add measepoch publishing - Add ChannelStatus parser - Add MeasEpoch parser - Add IMU and VelSensor setup parsers - Add Cov SBF parsers - Add templated qi parser function - Add AttEuler+Cov parser - Revert ordering change inside INSNav ROS msgs - Add ExtSensorMeas parser - Add PVT parsers - Add range checks to parsers - Replace INSNav grammar with parsers - Test parser vs. grammar for better performance - Fix sb_list check - Add IMU and VelSensor setup grammars - Move adapt ROS header to typedefs.h - Add revision check to MeasEpoch - Fix ReceiverStatus grammar - Extend ReceiverSetup and add revision checks - Change logger and fix loop range - Remove reserved bytes from parsing - Remove obsolete structs - Directly parse Cov SBFs to ROS msg - Directly parse PVT SBFs, remove obsolete ids - Rename rev to revision - Fix block header parsing - Directly parse AttEuler to ROS msg - Directly parse to ROS msgs for INSNavXxx - Exchange pow with square function and remove casts - Merge pull request #46 from thomasemter/dev/refactor Dev/refactor - Simplify sync bytes check - Move tow/wnc to BlockHeader - Adjust order in INSNav ros msgs - Fix INSNav grammars - Change BlockHeader structure - Remove length ref from header - Rectify sb_list check of INSNavXxx - Add automtatic activation of multi-antenna mode - Merge branch \'dev/refactor\' of https://github.com/thomasemter/septentrio_gnss_driver into dev/refactor - Add automtatic activation of multi-antenna mode - Fix wrong scope of phoenix::ref variables - Fix AttEuler grammar - Add max size checks to QualityInd and ReceiverStatus - Replace locals with phoenix::ref in grammars - Add revision dependent parsing to PVTs - Change offset check to epsilon - Change offset check to epsilon - Fix parsing checks - Set has arrived to false on parsing error - Add INSNav grammars - Add abs to offset check - Add abs to offset check - Add Cov grammars - Remove superfluous typdefs of structs - Add ReceiverStatus grammar - Add QualityINd grammar - Merge pull request #45 from thomasemter/dev/refactor Dev/refactor - Add id check to header grammar - Add id check to header grammar - Add ReceiverSetup grammar - Add DOP grammar - Directly intialize vector to parse - Add MeasEpoch grammar - Remove duplicate msg types - Remove obsolete include - Add revision and length return to header grammar - Merge branch \'feature/endianess_agnostic\' into dev/endianess_agnostic - Make multi_antenna option also usable for gnss - Add typedefs plus some minor changes - Add warning concerning pitch angle if antennas are rotated - Add multi antenna option to ins and fix antenna offset decimal places trimming - Fix identation - Distinguish between gnss and ins for spatial config from tf - Merge pull request #43 from thomasemter/dev/refactor Dev/refactor - Add vehicle frame for clarity - Handle missing tf more gently - Merge branch \'dev/spatial_config_via_tf\' into dev/refactor - Update readme - Fix antenna offset from tf - Add automatic publishing of localization if tf is activated - Add automatic publishing of localization if tf is activated - Add spatial config via tf, to be tested - Fix crashes due to parsing errors (replacing uncatched throws) - Add tf broadcasting - Add comments - Add localization in UTM output - Add check to IMU msg sync - Change msg sync to allow for 200 Hz IMU msgs - Add ROS IMU msg - Fix IMU setup message attitude conversion - Fix pose from INS data - Fix IMU raw data rotation compensation - Make antenna attitude offset usable by GNSS - Add ros directions option to pose and fix covariances - Update readme - Merge branch \'feature/ros_axis_orientation\' into dev/refactor - Add nmea_msgs dependencies - Merge branch \'dev/nmea\' into dev/refactor - Update readme - Update readme - Add antenna offsets to conversions - Fix IMU orientation conversion - Change ExtSensorMead temperature to deg C - Add axis orientation info to readme - Fix IMU axis orientation - Change get int param - Update readme to reflect removal of aux antenna offset - Fix different antenna setup message for INS and remove obsolete aux1 antenna offset for GNSS - Fix ExtSensorMeas message filling - Fix ExtSensorMeas message to reflect available fields - Fix missing INS blocks - Fix missing INS blocks - WIP, introduce ros axis orientation option, to be tested - Add option to set pvt rate to OnChange - Add comment on NTP to readme - Change to nmea_msgs - Add automatic addition of needed sub messages - Comment out setting debug level - Add comments and fix spelling errors - Merge pull request #42 from thomasemter/dev/refactor Dev/refactor - Change to quaternion msg typedef - Comment out debug logging - Remove filling of seq field - Change msg definitions to be compatible with ROS2 - Update readme - Change make_shared for portability and add more typedefs - Add get param int fallback for numeric antenna serial numbers - Change Attitude to be published with pvt rate - Add log identifier - Add checks for relevant ros params - Concatenate multiple SBF blocks in streams - Move main into own file - Move get ros time to AsyncManager - Remove obsolete param comment - Move get ros params to base class - Change to nsec timestamp internally - Add publishing functionality to node base class - Move node handle ptr and functions to base class and rename - Add stamp to nmea parsing - Add logging in PcapReader - Add logging in CircularBuffer - Add missed logging - Add logging in AsyncManager - Add getTime function - Add logging in RxMessage - Add logging in CallbackHandlers - Add log function to node by polymorphism, logging in Comm_OI - Fix wait function and force use_gnss_time when reading from file - Add thread shutdown and remove spurious delete - Add typedefs for ins messages - Add typedefs for gnss messages - Add typedefs for ros messages - Refine shutdown - Fix shutdown escalating to SIGTERM - Move waiting for response in send function - Make functions private - Change crc to C++ - Fix variable name - Remove global variables from node cpp file - Move more global settings to settings struct - Move more global settings to settings struct - Move global settings to settings struct - Move more functions to CommIo - Move settings to struct and configuration to CommIo - Merge branch \'dev/change_utc_calculation\' into dev/refactor - Remove obsolete global variables - Move g_unix_time to class - Make has_arrived booleans class memebers and rx_message a persistent class - Make node handle a class member - Fix parsing of ID and rev - Finish ChannelStatusGrammar, to be tested - WIP, partially fix ChannelStatusGrammar - Add SBF length parsing utility - Insert spirit parsers - WIP, add omission of padding bytes - WIP, add more spirit parsers - Add parsing utilities for tow, wnc and ID - Move getId/Tow/Wnc to parsing utilities - Change UTC calculation to use tow and wnc - WIP, add boost spirit and endian buffers - Change UTC calculation to use tow and wnc

  • Update Readme and Changelog

  • Contributors: Thomas Emter, Tibor Dome

1.0.8 (2021-10-23)

  • Added INS Support

1.0.7 (2021-05-18)

  • Clang formatting, publishing from SBF log, play-back of PCAP files

1.0.6 (2020-10-16)

  • ROSaic binary installation now available on Melodic & Noetic

1.0.5 (2020-10-15)

  • changed repo name
  • v1.0.4
  • 1.0.3
  • Merge pull request #22 from septentrio-gnss/local_tibor New changelog
  • New changelog
  • Merge pull request #21 from septentrio-gnss/local_tibor Added rosdoc.yaml file
  • Merge pull request #20 from septentrio-gnss/local_tibor Improved doxygen annotations
  • Merge pull request #19 from septentrio-gnss/local_tibor Improved doxygen annotations
  • Update README.md
  • Merge pull request #18 from septentrio-gnss/local_tibor Adopted ROS and C++ conventions, added ROS diagnostics msg,
  • Update README.md
  • Update README.md
  • Update README.md
  • Contributors: septentrio-users, tibordome

1.0.4 (2020-10-11)

  • Added rosdoc.yaml file
  • Improved doxygen annotations
  • Improved doxygen annotations
  • Adopted ROS and C++ conventions, added ROS diagnostics msg, removed ROS garbage value bug, added auto-detection of SBF arrival order for composite ROS msgs
  • Merge branch \'master\' of https://github.com/septentrio-gnss/rosaic
  • NTRIP with Datalink, circular buffer, reading connection descriptor, new messages
  • Update README.md
  • Contributors: septentrio-users, tibordome

1.0.3 (2020-09-30)

  • Add new config/rover.yaml file
  • Add config/rover.yaml to .gitignore
  • Merge pull request #17 from septentrio-gnss/local_tibor NTRIP with Datalink, circular buffer, reading connection descriptor..
  • Merge branch \'local_tibor\'
  • NTRIP with Datalink, circular buffer, reading connection descriptor, new messages
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #16 from septentrio-gnss/local_tibor NTRIP parameters added, reconnect_delay_s implemented,
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #15 from tibordome/local_tibor GPSFix completed, datum as new parameter
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #14 from tibordome/local_tibor GPSFix completed, datum as new parameter
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #13 from tibordome/local_tibor Added AttCovEuler.msg and AttEuler.msg
  • Merge pull request #12 from tibordome/local_tibor Fixed service field of NavSatStatus
  • Contributors: Tibor Dome, septentrio-users, tibordome

1.0.2 (2020-09-25)

  • NTRIP parameters added, reconnect_delay_s implemented, package.xml updated, ROSaic now detects connection descriptor automatically, mosaic serial port parameter added
  • GPSFix completed, datum as new parameter, ANT type and marker-to-arp distances as new parameters, BlockLength() method corrected, sending multiple commands to Rx corrected by means of mutex
  • Contributors: tibordome

1.0.1 (2020-09-22)

  • GPSFix completed, datum as new parameter, ANT type and marker-to-arp distances as new parameters, BlockLength() method corrected, sending multiple commands to Rx corrected by means of mutex
  • Added AttCovEuler.msg and AttEuler.msg
  • Fixed service field of NavSatStatus, fixed ROS header\'s seq field of each published ROS message, added write method for sending commands to Rx, successfully tested, added AttEuler, added AttCovEuler
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #11 from tibordome/local_tibor rosconsole_backend_interface dependency not needed
  • rosconsole_backend_interface dependency not needed
  • Merge pull request #10 from tibordome/local_tibor rosconsole_log4cxx dep not needed
  • rosconsole_log4cxx dep not needed
  • Merge pull request #9 from tibordome/local_tibor rosconsole_log4cxx dep not needed
  • rosconsole_log4cxx dep not needed
  • Merge pull request #8 from tibordome/local_tibor Local tibor
  • Update README.md
  • Merge pull request #7 from tibordome/local_tibor Ready for First Release
  • Update README.md
  • Update README.md
  • Update README.md
  • Merge pull request #6 from tibordome/local_tibor Local tibor
  • Merge pull request #5 from tibordome/local_tibor TCP seems to work
  • Contributors: Tibor Dome, tibordome

1.0.0 (2020-09-11)

  • Ready for first release
  • Added Gpgga.msg and PosCovGeodetic.msg files
  • Ready for First Release
  • Ready for first release
  • Ready for first release
  • Ready for first release
  • TCP bug removed
  • TCP bug removed
  • TCP seems to work
  • Merge pull request #4 from tibordome/v0.2 V0.2
  • PVTCartesian and PVTGeodetic publishing works on serial
  • PVTCartesian and PVTGeodetic publishing works on serial
  • Merge pull request #3 from tibordome/v0.2 Add doxygen_out and Doxyfile 2nd trial
  • Add doxygen_out and Doxyfile 2nd trial
  • Merge pull request #2 from tibordome/v0.1 Add doxygen_out and Doxyfile
  • Add doxygen_out and Doxyfile
  • Update README.md
  • Create README.md
  • Update LICENSE
  • Merge pull request #1 from tibordome/add-license-1 Create LICENSE
  • Create LICENSE
  • Create LICENSE
  • Commit
  • Successfully tested publishing to /gpgga topic via serial
  • To make sure master branch exists
  • Contributors: Tibor Dome, tibordome

Wiki Tutorials

See ROS Wiki Tutorials for more details.

Source Tutorials

Not currently indexed.

Recent questions tagged septentrio_gnss_driver at Robotics Stack Exchange