Source code for morse.middleware.ros.gps
from sensor_msgs.msg import NavSatFix
from morse.middleware.ros import ROSPublisher
[docs]class NavSatFixPublisher(ROSPublisher):
""" Publish the GPS position of the robot. """
ros_class = NavSatFix
[docs] def default(self, ci='unused'):
gps = NavSatFix()
gps.header = self.get_ros_header()
gps.latitude = self.data['x']
gps.longitude = self.data['y']
gps.altitude = self.data['z']
self.publish(gps)
[docs]class NavSatFixRawPublisher(ROSPublisher):
""" Publish the GPS position of the robot. """
ros_class = NavSatFix
[docs] def default(self, ci='unused'):
gps = NavSatFix()
gps.header = self.get_ros_header()
gps.latitude = self.data['latitude']
gps.longitude = self.data['longitude']
gps.altitude = self.data['altitude']
self.publish(gps)