in simulation_ws/src/robot_fleet/scripts/client_rosbridge.py [0:0]
def __init__(self):
self.data_to_rosbridge = {}
self.data_to_rosbridge['name'] = rospy.get_param('ROBOT_NAME')
self.data_to_rosbridge['robot_sdf_file'] = rospy.get_param('ROBOT_SDF_FILE')
self.data_to_rosbridge['navigation_pose'] = {}
self.data_to_rosbridge['gazebo_pose'] = {}
self.rosbridge_ip = rospy.get_param('ROSBRIDGE_IP')
self.rosbridge_state = rospy.get_param('ROSBRIDGE_STATE')
self.client = roslibpy.Ros(host=self.rosbridge_ip, port=9090)
self.client.run()
if self.rosbridge_state == 'CLIENT':
self.remap_pub = rospy.Publisher('remapped_client_robot_data', String, queue_size=1)
self.robot_data_listener = roslibpy.Topic(self.client, 'client_robot_data', 'std_msgs/String')
self.robot_data_listener.subscribe(self.remap_subscriber)
self.gazebo_model_state_sub = rospy.Subscriber('gazebo/model_states', ModelStates, self.model_states_callback, queue_size=1)
self.current_model_state = None
self.init_rosbridge_talkers()