From 6ae03fac5cf19f830f60e10a5bf669e0148a8e1f Mon Sep 17 00:00:00 2001
From: Mike Lautman <mikeblautman@gmail.com>
Date: Tue, 19 Mar 2019 23:19:17 -0600
Subject: [PATCH] fixing the virtual joint issue by adding the broadcaster
 (#23)

---
 launch/demo.launch | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/launch/demo.launch b/launch/demo.launch
index a8a9a86..61544a0 100644
--- a/launch/demo.launch
+++ b/launch/demo.launch
@@ -25,7 +25,7 @@
   </include>
 
   <!-- If needed, broadcast static tf for robot root -->
-
+  <node pkg="tf2_ros" type="static_transform_publisher" name="virtual_joint_broadcaster_1" args="0 0 0 0 0 0 1 world panda_link0" />
 
   <!-- We do not have a robot connected, so publish fake joint states -->
   <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
-- 
GitLab