cowdungcart_schedule.py 3.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687
  1. import pymysql
  2. import rospy
  3. from std_msgs.msg import String
  4. from geometry_msgs.msg import PoseStamped
  5. import json
  6. import threading
  7. from time import sleep as sl
  8. from datetime import datetime as dt
  9. class CowdungCart(object):
  10. def __init__(self):
  11. self.db = pymysql.connect(host='52.69.200.169', port=3306, user='cowdungcart', password='skyeye', database='CowdungCart', charset='utf8')
  12. self.cursor = self.db.cursor()
  13. def queryMySQL(self):
  14. while True:
  15. sl(60)
  16. # self.cursor.close()
  17. # self.db.close()
  18. # self.db = pymysql.connect(host='52.69.200.169', port=3306, user='cowdungcart', password='skyeye', database='CowdungCart', charset='utf8')
  19. # self.cursor = self.db.cursor()
  20. sql = "select time1, time2, time3, time4 from schedule order by datetime desc limit 1"
  21. self.cursor.execute(sql)
  22. schedules = self.cursor.fetchall()[0]
  23. current_time = dt.now()
  24. time = dt.strftime(current_time, "%H:%M")
  25. print(time)
  26. for schedule in schedules:
  27. print(schedule)
  28. if schedule == time:
  29. sql = "select goal_change_x, goal_change_y from goal"
  30. self.cursor.execute(sql)
  31. goals = self.cursor.fetchall()
  32. for goal in goals:
  33. self.goalPublish(goal)
  34. sl(600)
  35. def goalPublish(self, goal):
  36. # 定义发布器pub,发布的题目是chatter,消息类型是String,然后queue_size是在订阅者接受消息不够快的时候保留的消息的数量,如果对qos要求低的话可以设为0,不设置的话会出个报警,不过不会出错
  37. # pub = rospy.Publisher('chatter', String, queue_size=10)
  38. pub = rospy.Publisher('move_base_simple/goal', PoseStamped, queue_size=10)
  39. # 接下来这里初始化了一个名为talker的节点,节点的名字不能以‘ / ’开头,因为之后会自动给你加一个。anonymous参数在为True的时候会在原本节点名字的后面加一串随机数,来保证可以同时开启多个同样的节点,如果为false的话就只能开一个
  40. rospy.init_node('goalPublish', anonymous=True)
  41. # 这里初始化一个Rate对象,通过后面的sleep()可以设定循环的频率
  42. rate = rospy.Rate(10) # 10hz
  43. ps = PoseStamped()
  44. ps.header.seq = 0
  45. ps.header.stamp.secs = 0
  46. ps.header.stamp.nsecs = 0
  47. ps.header.frame_id = 'map'
  48. ps.pose.position.x = float(goal[0])
  49. ps.pose.position.y = float(goal[1])
  50. ps.pose.position.z = 0.0
  51. ps.pose.orientation.x = 0.0
  52. ps.pose.orientation.y = 0.0
  53. ps.pose.orientation.z = 0.2
  54. ps.pose.orientation.w = 0.1
  55. # rospy.loginfo(ps)
  56. # pub.publish(ps)
  57. # while not rospy.is_shutdown():
  58. # # hello_str = "hello world %s" % rospy.get_time()
  59. # rospy.loginfo(ps)
  60. # #这里把hello_str发布出去了
  61. # pub.publish(ps)
  62. # rate.sleep()
  63. i = 0
  64. while i < 2:
  65. rospy.loginfo(ps)
  66. pub.publish(ps)
  67. rate.sleep()
  68. i += 1
  69. def workOn(self):
  70. self.queryMySQL()
  71. self.cursor.close()
  72. self.db.close()
  73. if __name__ == '__main__':
  74. cowdungcart = CowdungCart()
  75. cowdungcart.workOn()