Binary Install
This repository hosts a ROS Melodic and Noetic driver (i.e. for Linux only) - written in C++ - that works with mosaic and AsteRx - two of Septentrio's cutting-edge GNSS and GNSS/INS receiver families - and beyond. Since Noetic will only be supported until 2025, a ROS2 version is available in the branch ros2
.
Main Features:
nav_msgs/Odometry
message for INS receiversPVTGeodetic
, PosCovGeodetic
, ChannelStatus
, MeasEpoch
, AttEuler
, AttCovEuler
, VelCovGeodetic
and DOP
in order to publish gps_common/GPSFix
and sensor_msgs/NavSatFix
messagesPlease let the maintainers know of your success or failure in using the driver with other devices so we can update this page appropriately.
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<br>
sudo apt install libboost-all-dev
.
Compatiblity with PCAP captures are incorporated through pcap libraries. Install the necessary headers via<br>
sudo apt install libpcap-dev
.
Conversions from LLA to UTM are incorporated through GeographicLib. Install the necessary headers via<br>
sudo apt install libgeographic-dev
<details>
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
. </details>
<details>
Build from Source
Alternatively, the package can also be built from source using catkin_tools
, 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 should suffice:
</details>
<details>
Notes Before Usage
roscd septentrio_gnss_driver
.setDefaultAccessLevel
command. If user control is in place user credentials can be given by parameters login/user
and login/password
.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.: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.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.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.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
.</details>
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.
<details>
Measure and Compensate for IMU-Antenna Lever Arm
The IMU/antenna position can be changed by specifying the lever arm's x
,y
and z
parameters in the config.yaml
file under the ins_spatial_config/ant_lever_arm
parameter.
</details>
<details>
Compensate for IMU Orientation
theta_x
,theta_y
and theta_z
in the config.yaml
file under the ins_spatial_config/imu_orientation
use_ros_axis_orientation: true
sensor_default is the top left position.</details>
receiver_type: ins
ins_spatial_config/imu_orientation
parameter.ins_spatial_config/ant_lever_arm
parameter. Specify ins_spatial_config/vsm_lever_arm
if measurements of a velocity sensor is available.get_spatial_config_from_tf
to true
in this case.ins_solution/poi_lever_arm
parameter.The following is a list of ROSaic parameters found in the config/rover.yaml
file.
Connectivity Specs
device
: location of device connectionserial:xxx
format for serial connections, where xxx is the device node, e.g. serial:/dev/ttyUSB0
file_name:path/to/file.sbf
format for publishing from an SBF logfile_name:path/to/file.pcap
format for publishing from PCAP capture.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 connections28784
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.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
.tcp://192.168.3.1:28784
serial
: specifications for serial communicationbaudrate
: 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 COM1hw_flow_control
: specifies whether the serial (the Rx's COM ports, not USB1 or USB2) connection to the Rx should have UART HW flow control enabled or notoff
to disable UART HW flow control, RTS|CTS
to enable it921600
, USB1
, off
login
: credentials for user authentication to perform actions not allowed to anonymous users. Leave empty for anonymous access.user
: user namepassword
: password </details><details>
Receiver Type
receiver_type
: This parameter is to select the type of the Septentrio receivergnss
for GNSS receivers.ins
for INS receivers.ins_in_gnss_mode
INS receivers in GNSS mode.gnss
multi_antenna
: Whether or not the Rx has multiple antennas.false
</details><details>
Frame ID
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.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.gnss
imu_frame_id
: name of the ROS tf frame for the IMU, placed in the header of published IMU messageimu
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
.base_link
vsm_frame_id
: name of the ROS tf frame for the velocity sensor.vsm
aux1_frame_id
: name of the ROS tf frame for the aux1 antenna.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.base_link
local_frame_id
: name of the ROS tf frame for the local frame.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.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.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.false
Septentrios definition is used, i.e., front-right-down body related frames and NED (north-east-down) for orientation frames.true
ROS definition is used, i.e., front-left-up body related frames and ENU (east-north-up) for orientation frames.true
</details><details>
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.true
</details><details>
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.Default
</details><details>
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.delta_e
, delta_n
and delta_u
are the offsets in the East, North and Up (ENU) directions respectively, expressed in meters.0.0
, 0.0
and 0.0
</details><details>
Antenna Attitude Offset
att_offset
: Angular offset between two antennas (Main and Aux) and vehicle frameheading
: The perpendicular (azimuth) axis can be compensated for by adjusting the heading
parameterpitch
: Vertical (elevation) offset can be compensated for by adjusting the pitch
parameter0.0
, 0.0
(degrees) </details><details>
Antenna Specs
ant_type
: type of your main GNSS antennalstAntennaInfo, Overview
. This is the list of antennas for which the receiver can compensate for phase center variation.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.Unknown
ant_serial_nr
: serial number of your main GNSS antennaant_aux1_type
and ant_aux1_serial_nr
: same for Aux1 antenna </details><details>
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.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. </details><details>
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
).sensor_msgs/NavSatFix.msg
or gps_common/GPSFix.msg
is triggered by the SBF block that arrives last among the blocks of the current epoch.500
(2 Hz)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 messages500
(2 Hz) </details><details>
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).true
</details><details>
RTK corrections
rtk_settings
: determines RTK connection parametersntrip_#
if the Rx has internet access and is able to receieve NTRIP streams from a caster. Up to three NTRIP connections are possible.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.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
.caster
: is the hostname or IP address of the NTRIP caster to connect to.caster_port
: IP port of the NTRIP caster.username
: user name for the NTRIP caster.pasword
: password for the NTRIP caster. The receiver encrypts the password so that it cannot be read back with the command "getNtripSettings".mountpoint
: mount point of the NTRP caster to be used.version
: argument specifies which version of the NTRIP protocol to use (v1
or v2
).tls
: determines wether to use TLS.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.rtk_standard
: determines the RTK standard, options are auto
, RTCMv2
, RTCMv3
, or CMRv2
.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.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.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.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.rtk_standard
: determines the RTK standard, options are auto
, RTCMv2
, RTCMv3
, or CMRv2
.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
.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.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.baud_rate
: sets the baud rate of this port for genuine serial ports, i.e., not relevant for USB connection.rtk_standard
: determines the RTK standard, options are auto
, RTCMv2
, RTCMv3
, or CMRv2
.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
.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.<details>
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 orientationtheta_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
.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.0.0
, 0.0
, 0.0
(degrees)poi_lever_arm
: The lever arm from the IMU reference point to a user-defined POIdelta_x
,delta_y
and delta_z
refer to the vehicle reference frame0.0
, 0.0
, 0.0
(meters)ant_lever_arm
: The lever arm from the IMU reference point to the main GNSS antennax
,y
and z
refer to the vehicle reference frame0.0
, 0.0
, 0.0
(meters)vsm_lever_arm
: The lever arm from the IMU reference point to the velocity sensorvsm_x
,vsm_y
and vsm_z
refer to the vehicle reference frame0.0
, 0.0
, 0.0
(meters)ins_initial_heading
: How the receiver obtains the initial INS/GNSS integrated heading during the alignment phaseauto
, the initial integrated heading is determined from GNSS measurements.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.auto
ins_std_dev_mask
: Maximum accepted erroratt_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)5
degrees, 10
metersins_use_poi
: Whether or not to use the POI defined in ins_spatial_config/poi_lever_arm
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.true
ins_vsm
: Configuration of the velocity sensor measurements.ros
: VSM info received from ROS msgssource
: 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
or geometry_msgs/TwistWithCovarianceStamped.msg
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
that twist should be specified in child_frame_id
.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.variances_by_parameter
: Wether variances shall be entered by parameter ins_vsm/ros/variances
or the values inside the messaged are used.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.ip_server
:id
: IP server to receive the VSM info (e.g. IPS2
).port
: TCP port to receive the VSM info. When selecting a port number, make sure to avoid conflicts with other services.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.true
serial
:port
: Serial port to receive the VSM info.baud_rate
: Baud rate of the serial port to receive the VSM info.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.true
</details><details>
Logger
activate_debug_log
: true
if ROS logger level shall be set to debug. </details>Parameters Configuring Publishing of ROS Messages <details>
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/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/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
respectivelypublish/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. </details>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
. <details>
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
./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)./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 header, or - if use_gnss_time
is set to false
- from the systems's wall-clock time./navsatfix
: publishes generic ROS message sensor_msgs/NavSatFix.msg
, converted from the SBF blocks PVTGeodetic
,PosCovGeodetic
(GNSS case) or INSNavGeod
(INS case).sensor_msgs/NavSatFix.msg
can be fed directly into the navsat_transform_node
of the ROS navigation stack./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)./pose
: publishes generic ROS message geometry_msgs/PoseWithCovarianceStamped.msg
, converted from the SBF blocks PVTGeodetic
, PosCovGeodetic
, AttEuler
, AttCovEuler
(GNSS case) or INSNavGeod
(INS case).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
.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.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. </details><details>
Some Ideas
host:port
specification, the driver could automatically search and establish a connection on the specified port.Data Link
. </details><details>
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:
.msg
file to the septentrio_gnss_driver/msg
folder.sbf_structs.hpp
file.septentrio_gnss_driver/PVTGeodetic.h
) that gets compiler-generated from the .msg
file constructed in step 3.NMEA_ID_Enum
enumeration in the rx_message.hpp
file with a new entry.RxIDMap
map in the rx_message.cpp
file with a new pair.io_comm_rx::RxMessage class
in the rx_message.hpp
file.rx_message.cpp
file.rx_message.hpp
file. It should be modeled on the existing evPVTGeodetic
case, e.g. one needs a static counter variable declaration.gpgga.cpp
to the septentrio_gnss_driver/src/septentrio_gnss_driver/parsers/nmea_parsers
folder and one such as gpgga.hpp
to the septentrio_gnss_driver/include/septentrio_gnss_driver/parsers/nmea_parsers
folder.publish/..
ROSaic parameter in the septentrio_gnss_driver/config/rover.yaml
file, create a global boolean variable publish_...
in the septentrio_gnss_driver/src/septentrio_gnss_driver/node/rosaic_node.cpp
file, insert the publishing callback function to the C++ "multimap" IO.handlers_.callbackmap_
- which is already storing all the others - in the rosaic_node::ROSaicNode::defineMessages()
method in the same file and add an extern bool publish_...;
line to the septentrio_gnss_driver/include/septentrio_gnss_driver/node/rosaic_node.hpp
file.septentrio_gnss_driver/CMakeLists.txt
file by adding a new entry to the add_message_files
section. </details>