Skip to main content

RTK Positioning

Hardware

The AutomatePro offers an optional RTK GNSS position sensor, giving it cm level positional accuracy. This is based on the Ublox F9P and R series devices and includes positional accuracy down to 2.5cm. If the option is included there will be a blue FAKRA connector for which the antenna can be connected to. "GNSS-2" is used for the position and "GNSS-1" is used for heading.

alt text

GNSS Position Specifications

ParameterValue
ReceiverUblox F9P or F9R (see Wheel Speed & Direction Input)
ConnectorGNSS-2 (FAKRA C - Signal Blue)
Supported ConstellationGPS, Galileo, BeiDou, GLONASS
Positional AccuracyDown to 1cm 1. Using Ublox point perfect correction <6cm
Max Navigation Update RateDefault 1Hz (Can be configured up to 7Hz)
Info

1 Depends on antenna, distance to base station or correction serivce - see the receiver datasheet for more information

External Antenna

The AutomatePro system is compatible with a variety of multi-band high precision GNSS antennas that have a FAKRA Type C connector (Signal Blue). To find more information on the antennas that have been used with AutomatePro, this can be found here

Wheel Speed & Direction Input

The AutomatePro provides options for both wheel speed and direction input for applications requiring dead reckoning.

Connection Details
Pin Name & NumberFunctionDescription
WHEEL TIC / PIN 51Tachometer input5-24VDC input range (with respect to the common GND)
WHEEL DIR / PIN 52Wheel rotation direction input5-24VDC input range (with respect to the common GND)
Important

This is a non-standard option - contact lemvos for more information

ROS API

Node: automatepro_gnss_position_node

Publishers

TopicTypeDescription
/sensor/gnss/position/fixsensor_msgs/msg/NavSatFixGNSS Position data (navigation satellite fix)
/sensor/gnss/position/fix_velocitygeometry_msgs/msg/
TwistWithCovarianceStamped
Velocity in local ENU frame.
/sensor/gnss/position/navposecefublox_msgs/msg/NavPOSECEFGNSS Position in ECEF (Earth-centered, Earth-fixed coordinate system) format
/sensor/gnss/position/mon_hwublox_msgs/msg/MonHWHardware and Firmware status of the GNSS position module
/sensor/gnss/position/nmeanmea_msgs/msg/SentenceRaw NMEA messages
/diagnosticsdiagnostic_msgs/msg/
DiagnosticArray
GNSS position ROS driver Diagnostics

Subscribers

TopicTypeDescription
/sensor/gnss/correctionrtcm_msgs/msg/MessageRTCM or SPARTN Correction data

Parameters

ParameterTypeValuesRuntime R/WDescription
devicestring/dev/ttyACM0read-onlySerial port (automatically configured)
frame_idstringgnss_positionread-onlyFrame id for the messages published
publish.allbooltrue/falseread-onlyPublish all the messages
publish.mon.hwbooltrue/falseread-onlyenable GNSS module diagnostics publishing
publish.nav.relposnedbooltrue/falseread-onlyenable NavRELPOSNED9 msg publishing set to false
publish.nav.headingbooltrue/falseread-onlyenable heading publishing set to false
publish.nmeabooltrue/falseread-onlyenable NMEA msg publishing
debugint0-4read-only0 - no debug msgs, 4 - all debug msgs

Configuration

Driver: automatepro_gnss_driver
Container: automatepro-core-driver

info

All the configuration related files can be found at /automatepro/config/ros directory.
These files will be mounted to docker container and will be used by the ROS driver.

config file can be found here.

~/.automatepro/config/ros/gnss_position_params.yaml

ROS Configuration

automatepro_gnss_position_node:
ros__parameters:
debug: 0

device: /dev/ttyACM0
frame_id: gnss_position

config_on_startup: false

# Publishers
publish:
all: false
mon:
hw: true
nav:
all: false
posllh: false
posecef: true
relposned: false
nmea: true
Important

Restart the automatepro-core-driver docker container after changing the configuration.
Configurations will only be applied after the container restarts.

docker restart automatepro-core-driver

Device Configuration

This section describes the configuration of the GNSS device. To explore the capabilities of the GNSS device, refer to the ublox documentation for more details.

You can use the pygpsclient GUI tool to configure the GNSS device. The video below demonstrates how to configure the GNSS device using the pygpsclient tool. Here is the configuration interface reference:

  1. Changing the navigation rate
  2. Changing the satellite preferences
  3. Changing the GNSS mode

Example

Example code snippets to read GNSS position data from the /sensor/gnss/position/fix topic.

import rclpy
from rclpy.node import Node
from sensor_msgs.msg import NavSatFix

class GNSSPositionSubscriber(Node):

def __init__(self):
super().__init__('gnss_position_subscriber')
self.subscription = self.create_subscription(
NavSatFix,
'/sensor/gnss/position/fix',
self.listener_callback,
10)

def listener_callback(self, msg):
self.get_logger().info('Latitude: %f' % msg.latitude)
self.get_logger().info('Longitude: %f' % msg.longitude)
self.get_logger().info('Altitude: %f' % msg.altitude)

def main(args=None):
rclpy.init(args=args)
node = GNSSPositionSubscriber()
rclpy.spin(node)
node.destroy_node()
rclpy.shutdown()

if __name__ == '__main__':
main()

Run the node using the following command:

ros2 run automatepro_python_tutorials gnss_position_node