Skip to main content
Version: Next

Monitor Location

Map location

The XY location of the platform in the 'map' coordinate frame. These values are relative to the datum coorodinate.

import rclpy
from rclpy.node import Node

from nav_msgs.msg import Odometry


class LocalizationOdom(Node):

def __init__(self):
super().__init__('localization_odom_sub')
self.odom_sub = self.create_subscription(
Odometry, 'localization/odom', self.odom_cb, 10)
self.odom_sub # prevent unused variable warning

def odom_cb(self, msg):
self.last_odom_msg = msg

if __name__ == '__main__':
rclpy.init(args=args)
localization_odom_sub = LocalizationOdom()
rclpy.spin(localization_odom_sub)
localization_odom_sub.destroy_node()
rclpy.shutdown()

Lat/Lon location

The lat/lon location of the platform.

import rclpy
from rclpy.node import Node

from sensor_msgs.msg import NavSatFix


class LocalizationFix(Node):

def __init__(self):
super().__init__('localization_fix_sub')
self.odom_sub = self.create_subscription(
NavSatFix, 'localization/fix', self.fix_cb, 10)
self.fix_sub # prevent unused variable warning

def fix_cb(self, msg):
self.last_fix_msg = msg

if __name__ == '__main__':
rclpy.init(args=args)
localization_fix_sub = LocalizationFix()
rclpy.spin(localization_fix_sub)
localization_fix_sub.destroy_node()
rclpy.shutdown()