Go to the documentation of this file.00001
00002
00003 import rospy
00004 from std_msgs.msg import Empty
00005
00006 class gazebo_topics():
00007
00008 def __init__(self):
00009
00010 self.joy_usage_pub = rospy.Publisher("/joy_usage", Empty, queue_size=1)
00011 self.pc1_usage_pub = rospy.Publisher("/pc1_usage", Empty, queue_size=1)
00012 self.pc2_usage_pub = rospy.Publisher("/pc2_usage", Empty, queue_size=1)
00013 self.pc3_usage_pub = rospy.Publisher("/pc3_usage", Empty, queue_size=1)
00014 self.b1_usage_pub = rospy.Publisher("/b1_usage", Empty, queue_size=1)
00015 self.t1_usage_pub = rospy.Publisher("/t1_usage", Empty, queue_size=1)
00016 self.t2_usage_pub = rospy.Publisher("/t2_usage", Empty, queue_size=1)
00017 self.t3_usage_pub = rospy.Publisher("/t3_usage", Empty, queue_size=1)
00018 self.wifi_status_pub = rospy.Publisher("/wifi_status", Empty, queue_size=1)
00019
00020 rospy.sleep(0.5)
00021
00022
00023 if __name__ == "__main__":
00024 rospy.init_node('gazebo_topics')
00025 gt = gazebo_topics()
00026 rospy.loginfo("gazebo_topics running")
00027
00028 rate = rospy.Rate(1)
00029 while not rospy.is_shutdown():
00030 msg = Empty()
00031 gt.joy_usage_pub.publish(msg)
00032 gt.pc1_usage_pub.publish(msg)
00033 gt.pc2_usage_pub.publish(msg)
00034 gt.pc3_usage_pub.publish(msg)
00035 gt.b1_usage_pub.publish(msg)
00036 gt.t1_usage_pub.publish(msg)
00037 gt.t2_usage_pub.publish(msg)
00038 gt.t3_usage_pub.publish(msg)
00039 gt.wifi_status_pub.publish(msg)
00040 try:
00041 rate.sleep()
00042 except rospy.ROSInterruptException as e:
00043
00044 pass
00045