From 808cd1c3aa5bd836f9f71fb00d980ca8d748e89a Mon Sep 17 00:00:00 2001
From: Reed Hedges <reed@interreality.org>
Date: Thu, 19 Nov 2015 13:08:07 -0500
Subject: [PATCH] in LaserPublisher rename default global tf to "odom"

---
 LaserPublisher.h | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/LaserPublisher.h b/LaserPublisher.h
index bd9f0fd..51a65d4 100644
--- a/LaserPublisher.h
+++ b/LaserPublisher.h
@@ -12,7 +12,7 @@ class ArTime;
 class LaserPublisher
 {
 public:
-  LaserPublisher(ArLaser* _l, ros::NodeHandle& _n, bool _broadcast_transform = true, const std::string& _tf_frame = "laser_frame", const std::string& _parent_tf_frame = "base_link", const std::string& _global_tf_frame = "map");
+  LaserPublisher(ArLaser* _l, ros::NodeHandle& _n, bool _broadcast_transform = true, const std::string& _tf_frame = "laser", const std::string& _parent_tf_frame = "base_link", const std::string& _global_tf_frame = "odom");
   ~LaserPublisher();
 protected:
   void readingsCB();
-- 
GitLab