diff --git a/stretch_gazebo/launch/gazebo.launch b/stretch_gazebo/launch/gazebo.launch
index 87530b0..ddf6a02 100644
--- a/stretch_gazebo/launch/gazebo.launch
+++ b/stretch_gazebo/launch/gazebo.launch
@@ -49,6 +49,6 @@
-
+
diff --git a/stretch_gazebo/package.xml b/stretch_gazebo/package.xml
index c40d3b8..1debea1 100644
--- a/stretch_gazebo/package.xml
+++ b/stretch_gazebo/package.xml
@@ -15,15 +15,18 @@
controller_manager
gazebo_msgs
gazebo_plugins
+ gazebo_ros_control
gazebo_ros
nav_msgs
realsense_gazebo_plugin
realsense2_camera
realsense2_description
robot_state_publisher
+ ros_controllers
rospy
rviz
std_msgs
+ teleop_twist_joy
xacro
diff --git a/stretch_gazebo/scripts/publish_ground_truth_odom.py b/stretch_gazebo/scripts/publish_ground_truth_odom.py
index ce3ac42..f6ee321 100755
--- a/stretch_gazebo/scripts/publish_ground_truth_odom.py
+++ b/stretch_gazebo/scripts/publish_ground_truth_odom.py
@@ -1,6 +1,6 @@
#! /usr/bin/env python3
-from gazebo_msgs.srv import GetModelState, GetModelStateRequest
+from gazebo_msgs.srv import GetModelState, GetModelStateRequest, GetWorldProperties
from nav_msgs.msg import Odometry
from std_msgs.msg import Header
import rospy
@@ -10,20 +10,25 @@ odom_pub=rospy.Publisher('ground_truth', Odometry, queue_size=10)
rospy.wait_for_service ('/gazebo/get_model_state')
get_model_srv = rospy.ServiceProxy('/gazebo/get_model_state', GetModelState)
+get_world_properties = rospy.ServiceProxy('/gazebo/get_world_properties', GetWorldProperties)
odom=Odometry()
header = Header()
header.frame_id='/ground_truth'
model = GetModelStateRequest()
model.model_name='robot'
-
+models = []
r = rospy.Rate(20)
while not rospy.is_shutdown():
- result = get_model_srv(model)
- odom.pose.pose = result.pose
- odom.twist.twist = result.twist
- header.stamp = rospy.Time.now()
- odom.header = header
- odom_pub.publish(odom)
+ if model.model_name not in models:
+ models = get_world_properties().model_names
+ rospy.logwarn("Waiting for %s to spawn to publish ground truth odometry", model.model_name)
+ else:
+ result = get_model_srv(model)
+ odom.pose.pose = result.pose
+ odom.twist.twist = result.twist
+ header.stamp = rospy.Time.now()
+ odom.header = header
+ odom_pub.publish(odom)
r.sleep()
diff --git a/stretch_moveit_config/package.xml b/stretch_moveit_config/package.xml
index 6e3e179..99abf10 100644
--- a/stretch_moveit_config/package.xml
+++ b/stretch_moveit_config/package.xml
@@ -24,6 +24,7 @@
moveit_ros_move_group
moveit_ros_visualization
moveit_setup_assistant
+ moveit_simple_controller_manager
robot_state_publisher
stretch_description
tf2_ros