Show EOL distros:
Package Summary
Provides a ublox_gps node for uBlox GPS receivers and message and serialization packages for the binary UBX protocol.
- Author: Johannes Meyer
- License: BSD
- Source: git https://github.com/tu-darmstadt-ros-pkg/ublox (branch: None)
Package Summary
Provides a ublox_gps node for uBlox GPS receivers and message and serialization packages for the binary UBX protocol.
- Author: Johannes Meyer
- License: BSD
- Source: git https://github.com/tu-darmstadt-ros-pkg/ublox.git (branch: None)
Package Summary
Provides a ublox_gps node for uBlox GPS receivers and message and serialization packages for the binary UBX protocol.
- Maintainer: Johannes Meyer <meyer AT fsr.tu-darmstadt DOT de>
- Author: Johannes Meyer <meyer AT fsr.tu-darmstadt DOT de>
- License: BSD
- Bug / feature tracker: http://github.com/tu-darmstadt-ros-pkg/ublox/issues
- Source: git https://github.com/tu-darmstadt-ros-pkg/ublox.git (branch: None)
Package Summary
Provides a ublox_gps node for uBlox GPS receivers and message and serialization packages for the binary UBX protocol.
- Maintainer: Johannes Meyer <meyer AT fsr.tu-darmstadt DOT de>
- Author: Johannes Meyer <meyer AT fsr.tu-darmstadt DOT de>
- License: BSD
- Bug / feature tracker: http://github.com/tu-darmstadt-ros-pkg/ublox/issues
- Source: git https://github.com/tu-darmstadt-ros-pkg/ublox.git (branch: catkin)
Package Summary
Provides a ublox_gps node for u-blox GPS receivers, messages, and serialization packages for the binary UBX protocol.
- Maintainer status: maintained
- Maintainer: Veronica Lane <vmlane AT alum.mit DOT edu>
- Author: Johannes Meyer
- License: BSD
- Source: git https://github.com/KumarRobotics/ublox.git (branch: master)
Package Summary
Provides a ublox_gps node for u-blox GPS receivers, messages, and serialization packages for the binary UBX protocol.
- Maintainer status: maintained
- Maintainer: Veronica Lane <vmlane AT alum.mit DOT edu>
- Author: Johannes Meyer
- License: BSD
- Source: git https://github.com/KumarRobotics/ublox.git (branch: master)
Package Summary
Provides a ublox_gps node for u-blox GPS receivers, messages, and serialization packages for the binary UBX protocol.
- Maintainer status: maintained
- Maintainer: Veronica Lane <vmlane AT alum.mit DOT edu>
- Author: Johannes Meyer
- License: BSD
- Source: git https://github.com/KumarRobotics/ublox.git (branch: master)
Package Summary
Provides a ublox_gps node for u-blox GPS receivers, messages, and serialization packages for the binary UBX protocol.
- Maintainer status: maintained
- Maintainer: Veronica Lane <vmlane AT alum.mit DOT edu>
- Author: Johannes Meyer
- License: BSD
- Source: git https://github.com/KumarRobotics/ublox.git (branch: master)
Package Summary
Provides a ublox_gps node for u-blox GPS receivers, messages, and serialization packages for the binary UBX protocol.
- Maintainer status: maintained
- Maintainer: Veronica Lane <vmlane AT alum.mit DOT edu>
- Author: Johannes Meyer
- License: BSD
- Source: git https://github.com/KumarRobotics/ublox.git (branch: master)
Overview
This package provides basic device handling for u-blox GPS devices.
The driver publishes sensor_msgs/NavSatFix and geometry_msgs/TwistWithCovarianceStamped messages. The ublox_gps package provides a node to subscribe to various u-blox messages.
ROS Node
ublox_gps
ROS node that captures u-blox data and publishes fix and velocity messages as well as raw messages.Published Topics
~<node_name>/fix (sensor_msgs/NavSatFix)- GNSS Fix in the gps frame of reference.
- GNSS Fix Velocity in the gps frame of reference.
- Diagnostic status information.
Parameters
all
Parameters for all product types.- Transform frame ID for the device (resolved using tf_prefix, if defined).
- Path of port to read.
- Bit rate of the serial communication.
- UART1 in communication protocol. ublox_msgs/CfgPRT message for possible values.
- UART1 out communication protocol. See ublox_msgs/CfgPRT message for possible values.
- Rate in Hz of measurements.
- How often navigation solutions are published in number of measurement cycles.
- Enable precise-point-positioning system.
- Enable satellite-based augmentation system.
- SBAS Usage (e.g. ranging source, differential corrections, or integrity information). See ublox_msgs/CfgSBAS message for details.
- Possible values:
- portable
- stationary
- pedestrian
- automotive
- sea
- airborne1 (Airborne, max acceleration = 1G)
- airborne2 (Airborne, max acceleration = 2G)
- airborne4 (Airborne, max acceleration = 4G)
- wristwatch
- Type of fixes supported
- 2d
- 3d
- both
- Max time in seconds to use dead reckoning after signal is lost.
- If true, the node will send a ublox_msgs/UpdSOS command to save the BBR to flash memory on shutdown. Firmware >= 8 only.
- If true, the node will send a ublox_msgs/UpdSOS command to clear the flash memory during configuration. Firmware >= 8 only.
- Whether or not the device is a Raw Data Product (Firmware 6-7.03 only).
Save/Load
Save configuration to & load configuration from non-volatile memory. See ublox_msgs/CfgCFG.- Mask with configuration sub-sections to save to memory.
- Mask which selects the devices to save to.
- Mask with configuration sub-sections to Load form memory. Loading I/O will cause the serial port to reset.
- Mask which selects the devices to load from.
datum
User defined datum parameters- Whether to configure the datum based on the ~<node_name>/dat parameters. If true, the parameters below are required.
- Semi-major Axis [m]. Accepted range = 6,300,000.0 to 6,500,000.0.
- 1.0 / Flattening
- [X, Y, Z]-axis shift [m]. Accepted range is +/- 5000.0 meters
- [X, Y, Z]-axis rotation [s]. Accepted range is +/- 20.0 milli-arc seconds.
- scale change [ppm]. Accepted range is 0.0 to 50.0 parts per million.
gnss
GNSS parameters for firmware >= 7. Some parameters only apply to firmware >= 8 (see descriptions).- Enable GPS receiver.
- Enable GLONASS receiver.
- Enable BeiDou receiver.
- Enable QZSS receiver.
- QZSS signal configuration. See ublox_msgs/CfgGNSS message for constants.
- Enable Galileo receiver. Firmware >= 8 only.
- Enable IMES receiver. Firmware >= 8 only.
nmea
NMEA configuration for Firmware >= 7.- If true, the NMEA will be configured.
- NMEA version. Must be set if nmea/set is true.
- Maximum Number of SVs to report per TalkerId. Must be set if nmea/set is true.
- Configures the display of satellites that do not have an NMEA-defined value. Must be set if nmea/set is true.
- Enable compatibility mode. Must be set if nmea/set is true.
- Enable considering mode. Must be set if nmea/set is true.
- Enable strict limit to 82 characters maximum.
- Enable high precision mode.
- Enable position output for failed or invalid fixes.
- Enable position output for invalid fixes.
- Enable time output for invalid times.
- Enable date output for invalid dates.
- Restrict output to GPS satellites only.
- Enable COG output even if COG is frozen.
- Disable reporting of GPS satellites.
- Disable reporting of SBAS satellites.
- Disable reporting of QZSS satellites.
- Disable reporting of GLONASS satellites.
- Disable reporting of BeiDou satellites.
- This field enables the main Talker ID to be overridden.
- This field enables the GSV Talker ID to be overridden.
- Sets the two characters that should be used for the BeiDou Talker ID. Firmware >= 8 only.
nmea6
NMEA settings for Firmware version 6.- If true, the NMEA will be configured with the parameters below.
- NMEA version. Must be set if nmea/set is true.
- Maximum Number of SVs to report per Talker Id. Must be set if nmea/set is true.
- Enable compatibility mode. Must be set if nmea/set is true.
- Enable considering mode. Must be set if nmea/set is true.
- Disable position filtering.
- Disable masked position filtering.
- Disable time filtering.
- Disable date filtering.
- Enable SBAS filtering.
- Disable track filtering.
ADR/UDR
Parameters for Automotive Dead Reckoning and Untethered Dead Reckoning devices- Enable ADR/UDR.
- Same parameter as described in all section, but for ADR/UDR products it must be set to 1 Hz (therefore, set it equal to the rate).
HPG Reference
Parameters for High Precision GNSS (HPG) Reference station devices- Time Mode. Required. See ublox_msgs/CfgTMODE3 for constants.
- True if the Fixed position is in Lat, Lon, Alt coordinates. False if ECEF. Required if tmode3 is set to fixed.
- Antenna Reference Point position in [m] or [deg]. Required if tmode3 is set to fixed.
- Antenna Reference Point High Precision position in [0.1 mm] or [deg * 1e-9]. Required if tmode3 is set to fixed.
- Fixed position accuracy in [m]. Required if tmode3 is set to fixed.
- Whether or not to reset the survey in upon initialization. If false, it will only reset if the TMODE is disabled.
- The minimum Survey-In Duration time in seconds. Required if tmode3 is set to survey in.
- The minimum accuracy level of the survey in position in meters. Required if tmode3 is set to survey in.
HPG Rover
Parameters for High Precision GNSS Rover devices- The Differential GNSS mode. Defaults to RTK FIXED. See ublox_msgs/CfgDGNSS for constants.
INF messages
Enable printing INF messages to the ROS console.- This is the default value for the INF parameters below, which enable printing u-blox INF messages to the ROS console. Individual INF message types can be turned off by setting their corresponding parameter to false.
- Whether to configure the UBX and NMEA ports to send Debug messages and print received INF-Debug messages to ROS_DEBUG console.
- Whether to enable Error messages for the UBX and NMEA ports and print received INF-Error messages to ROS_ERROR console.
- Whether to enable Notice messages for the UBX and NMEA ports and print received INF-Notice messages to ROS_INFO console.
- Whether to enable Test messages for the UBX and NMEA ports and print received INF-Test messages to ROS_INFO console.
- Whether to enable Warning messages for the UBX and NMEA ports and print received INF-Warning messages to the ROS_WARN console.
u-blox message publishers
Set the parameters below to subscribe to the specific u-blox message and publish on a ROS topic.- This is the default value for the RXM, AID, MON, etc. publish/<class>/all parameters below. Individual message classes and messages can be turned off by setting the parameter described below to false.
- This is the default value for the AID subscriber parameters below. Individual AID message subscribers can be turned off by setting the parameter below to false.
- Whether to subscribe to u-blox AidALM messages and publish on the ~aidalm topic.
- Whether to subscribe to u-blox AidEPH messages and publish on the ~aideph topic.
- Whether to subscribe to u-blox AidHUI messages and publish on the ~aidhui topic.
- This is the default value for the RXM subscriber parameters below. Individual RXM message subscribers can be turned off by setting the parameter below to false
- Whether to subscribe to u-blox RxmALM messages and publish on the ~rxmalm topic.
- Whether to subscribe to u-blox RxmRAW messages and publish on the ~rxmraw topic.
- Whether to subscribe to u-blox RxmRTCM messages and publish on the ~rxmrtcm topic.
- Whether to subscribe to u-blox RxmSFRB messages and publish on the ~rxmsfrb topic.
- Whether to subscribe to u-blox RxmEPH messages and publish on the ~rxmeph topic.
- This is the default value for the MON subscriber parameters below. It defaults to true. Individual messages can be turned off by setting the parameter below to false.
- Whether to subscribe to u-blox MonHW messages and publish on the ~monhw topic.
- Whether to subscribe to u-blox NavATT messages and publish on the ~navatt topic. on ADR and UDR devices only
- Whether to subscribe to u-blox NavCLOCK messages and publish on the ~navclock topic.
- Whether to subscribe to u-blox NavPOSECEF messages and publish on the ~navposecef topic.
- Whether to publish NavPOSLLH messages on the ~navposllh topic. Firmware <= 6 only, for firmware 7 and above, use NavPVT messages.
- Whether to publish NavPVT messages on the ~navpvt topic. Firmware >= 7 only.
- Whether to publish NavRELPOSNED messages on the ~navrelposned topic. HPG Rover devices only.
- Whether to subscribe to u-blox NavSAT messages and publish on the ~navsat topic.
- Whether to publish NavSOL messages on the ~navsol topic. Firmware <= 6 only. For firmware 7 and above, use NavPVT messages.
- Whether to subscribe to u-blox NavSTATUS messages and publish on the ~navstatus topic.
- Whether to publish NavSVIN messages on the ~navsvin topic. HPG Reference Station devices only
- Whether to subscribe to u-blox NavSVINFO messages and publish on the ~navsvinfo topic.
- Whether publish ublox_msgs/NavVELNED messages on the ~navvelned topic. Firmware <= 6 only. For 7 and above, use ublox_msgs/NavPVT.
- This is the default value for the ESF subscriber parameters below. It defaults to true for ADR/UDR devices. Individual messages can be turned off by setting the parameter below to false.
- Whether to subscribe to u-blox EsfINS messages and publish on the ~esfins topic.
- Whether to subscribe to u-blox EsfMEAS messages and publish on the ~esfmeas topic.
- Whether to subscribe to u-blox EsfRAW messages and publish on the ~esfraw topic.
- Whether to subscribe to u-blox EsfSTATUS messages and publish on the ~esfstatus topic.
- Whether to subscribe to u-blox HnrPVT messages and publish on the ~hnrpvt topic.
Launch
Launch the ublox_gps node. Since there are many parameters, load the parameters from a .yaml file. For example:
<?xml version="1.0" encoding="UTF-8"?> <launch> <arg name="param_file_name" doc="name of param file, e.g. rover" /> <node pkg="ublox_gps" type="ublox_gps" name="ublox_gps"> <rosparam command="load" file="$(find ublox_gps)/config/$(arg param_file_name).yaml" /> </node> </launch>
An example parameter file is shown below. Note that if the baudrate, rate, nav_rate or GNSS are not configured correctly for your device, the launch may fail.
debug: 1 # Range 0-4 (0 means no debug statements will print) device: /dev/ttyACM0 frame_id: gps dynamic_model: portable fix_mode: auto # Switches between 2D/3D automatically dr_limit: 0 # Dead reckoning limit enable_ppp: false # Advanced setting not supported by all devices rate: 4 # Measurement rate in Hz nav_rate: 4 # in number of measurement cycles uart1: baudrate: 19200 # baudrate is device specific, check the device manual in: 1 # UBX out: 4 # RTCM # RTCM out config rtcm: ids: [5, 87, 77, 230] # RTCM Messages to configure rates: [1, 1, 1, 10] # Rates of RTCM messages above, # in number of navigation solutions dat: set: false # Do not set the user configured datum # GNSS Config, verify which GNSS are supported by your device gnss: gps: true # (not required since it defaults to true) glonass: true beidou: false qzss: false sbas: false inf: all: true # Whether to display INF messages # Message subscriptions subscribe: all: true # Subscribe to all messages aid: all: false # ... except AID messages