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.
GNSS Position Specifications
Parameter | Value |
---|---|
Receiver | Ublox F9P or F9R (see Wheel Speed & Direction Input) |
Connector | GNSS-2 (FAKRA C - Signal Blue) |
Supported Constellation | GPS, Galileo, BeiDou, GLONASS |
Positional Accuracy | Down to 1cm 1. Using Ublox point perfect correction <6cm |
Max Navigation Update Rate | Default 1Hz (Can be configured up to 7Hz) |
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 & Number | Function | Description |
---|---|---|
WHEEL TIC / PIN 51 | Tachometer input | 5-24VDC input range (with respect to the common GND) |
WHEEL DIR / PIN 52 | Wheel rotation direction input | 5-24VDC input range (with respect to the common GND) |
- Connector
- Development Breakout Board


This is a non-standard option - contact lemvos for more information
ROS API
Node: automatepro_gnss_position_node
Publishers
Topic | Type | Description |
---|---|---|
/sensor/gnss/position/fix | sensor_msgs/msg/NavSatFix | GNSS Position data (navigation satellite fix) |
/sensor/gnss/position/fix_velocity | geometry_msgs/msg/ TwistWithCovarianceStamped | Velocity in local ENU frame. |
/sensor/gnss/position/navposecef | ublox_msgs/msg/NavPOSECEF | GNSS Position in ECEF (Earth-centered, Earth-fixed coordinate system) format |
/sensor/gnss/position/mon_hw | ublox_msgs/msg/MonHW | Hardware and Firmware status of the GNSS position module |
/sensor/gnss/position/nmea | nmea_msgs/msg/Sentence | Raw NMEA messages |
/diagnostics | diagnostic_msgs/msg/ DiagnosticArray | GNSS position ROS driver Diagnostics |
Subscribers
Topic | Type | Description |
---|---|---|
/sensor/gnss/correction | rtcm_msgs/msg/Message | RTCM or SPARTN Correction data |
Parameters
Parameter | Type | Values | Runtime R/W | Description |
---|---|---|---|---|
device | string | /dev/ttyACM0 | read-only | Serial port (automatically configured) |
frame_id | string | gnss_position | read-only | Frame id for the messages published |
publish.all | bool | true/false | read-only | Publish all the messages |
publish.mon.hw | bool | true/false | read-only | enable GNSS module diagnostics publishing |
publish.nav.relposned | bool | true/false | read-only | enable NavRELPOSNED9 msg publishing set to false |
publish.nav.heading | bool | true/false | read-only | enable heading publishing set to false |
publish.nmea | bool | true/false | read-only | enable NMEA msg publishing |
debug | int | 0-4 | read-only | 0 - no debug msgs, 4 - all debug msgs |
Configuration
Driver: automatepro_gnss_driver
Container: automatepro-core-driver
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
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:
- Changing the navigation rate
- Changing the satellite preferences
- Changing the GNSS mode
Example
Example code snippets to read GNSS position data from the /sensor/gnss/position/fix
topic.
- Python
- C++
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
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/NavSatFix.hpp>
class GNSSPositionSubscriber : public rclcpp::Node
{
public:
GNSSPositionSubscriber()
: Node("gnss_position_subscriber")
{
subscription_ = this->create_subscription<sensor_msgs::msg::NavSatFix>(
"/sensor/gnss/position/fix",
10,
std::bind(&GNSSPositionSubscriber::listener_callback, this, std::placeholders::_1));
}
private:
void listener_callback(const sensor_msgs::msg::NavSatFix::SharedPtr msg)
{
RCLCPP_INFO(this->get_logger(), "Latitude: %f", msg->latitude);
RCLCPP_INFO(this->get_logger(), "Longitude: %f", msg->longitude);
RCLCPP_INFO(this->get_logger(), "Altitude: %f", msg->altitude);
}
rclcpp::Subscription<sensor_msgs::msg::NavSatFix>::SharedPtr subscription_;
};
int main(int argc, char *argv[])
{
rclcpp::init(argc, argv);
auto node = std::make_shared<GNSSPositionSubscriber>();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
Run the node using the following command:
ros2 run automatepro_cpp_tutorials gnss_position_node