From d14cfe50a46c4225db4ff6b05de6954bf30de259 Mon Sep 17 00:00:00 2001
From: Erik Andresen <erik@vontaene.de>
Date: Tue, 8 Aug 2017 22:08:39 +0200
Subject: [PATCH] gps: set frame_id to "gps"

---
 launch/gps.launch | 3 ++-
 1 file changed, 2 insertions(+), 1 deletion(-)

diff --git a/launch/gps.launch b/launch/gps.launch
index bcce41d..60a87f4 100644
--- a/launch/gps.launch
+++ b/launch/gps.launch
@@ -2,11 +2,12 @@
 <launch>
 	<node pkg="gpsd_client" type="gpsd_client"  name="gpsd_client" output="screen">
 		<param name="use_gps_time" value="false"/>
+		<param name="frame_id" value="gps"/>
 	</node>
 
 	<node pkg="robot_localization" type="navsat_transform_node" name="navsat_transform_node" output="screen">
 		<param name="magnetic_declination_radians" value="0.047"/>
-		<param name="yaw_offset" value="1.5708"/>
+		<param name="yaw_offset" value="0.0"/>
 		<param name="zero_altitude" value="true"/>
 		<param name="broadcast_utm_transform" value="true"/>
 
-- 
2.39.5