in simulation_ws/src/robot_fleet/scripts/client_rosbridge.py [0:0]
def main(self):
rate = rospy.Rate(10.0)
listener = tf.TransformListener()
while not rospy.is_shutdown():
try:
(trans,rot) = listener.lookupTransform('map', '/base_link', rospy.Time(0))
nav_pose = {}
nav_pose['x'] = trans[0]
nav_pose['y'] = trans[1]
nav_pose['z'] = trans[2]
nav_pose['qx'] = rot[0]
nav_pose['qy'] = rot[1]
nav_pose['qz'] = rot[2]
nav_pose['qw'] = rot[3]
self.data_to_rosbridge['navigation_pose'] = nav_pose
gazebo_pose = {}
gazebo_model_index = self.current_model_state.name.index("/") # Looking for main robot which in under namespace "/"
gz_pose = self.current_model_state.pose[gazebo_model_index]
gazebo_pose['x'] = gz_pose.position.x
gazebo_pose['y'] = gz_pose.position.y
gazebo_pose['z'] = gz_pose.position.z
gazebo_pose['qx'] = gz_pose.orientation.x
gazebo_pose['qy'] = gz_pose.orientation.y
gazebo_pose['qz'] = gz_pose.orientation.z
gazebo_pose['qw'] = gz_pose.orientation.w
self.data_to_rosbridge['gazebo_pose'] = gazebo_pose
self.talker.publish(roslibpy.Message( {'data': json.dumps(self.data_to_rosbridge)} ))
except (tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException):
rospy.loginfo("[client_rosbridge] TF exception in gathering current position")
rate.sleep()