pubGoal.py 5.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197
  1. #!/usr/bin/env python3
  2. import rospy
  3. # from std_msgs.msg import String
  4. from hinge_car_nav_msgs.msg import HingeCarNavActionGoal
  5. from hinge_car_nav_msgs.msg import hinge_car_nav_msgs
  6. import geometry_msgs.msg
  7. # import numpy as np
  8. # import sys
  9. # Brings in the SimpleActionClient
  10. import yaml
  11. import actionlib
  12. # Brings in the messages used by the fibonacci action, including the
  13. # goal message and the result message.
  14. # from tf.transformations import quaternion_from_euler
  15. def callback(data):
  16. # rospy.loginfo(rospy.get_caller_id() + 'I heard %s', )
  17. rospy.loginfo('received move base action goal')
  18. # rospy.loginfo(data.goal_id)
  19. def done_cb(data, data1):
  20. print("action done cb:%d,%s" % (data, data1))
  21. def active_cb():
  22. print("active_cb")
  23. def feedback_cb(data):
  24. pass
  25. # print("feedback_cb x:%f,y%f", data.pose.position.x,data.pose.position.y)
  26. # print("feedback_cb ", data.base_position.pose.position.x )
  27. if __name__ == '__main__':
  28. # In ROS, nodes are uniquely named. If two nodes with the same
  29. # name are launched, the previous one is kicked off. The
  30. # anonymous=True flag means that rospy will choose a unique
  31. # name for our 'listener' node so that multiple listeners can
  32. # run simultaneously.
  33. rospy.init_node('action_client', anonymous=True)
  34. # rospy.Subscriber('/perception/traffic_light_recognition/output/rois', String, callback)
  35. # rospy.Subscriber('/move_base/goal',MoveBaseActionGoal, callback)
  36. # goal_pub = rospy.Publisher('/move_base/goal',MoveBaseActionGoal)
  37. # (FibonacciAction) to the constructor.
  38. client = actionlib.SimpleActionClient(
  39. 'hinge_car_nav', hinge_car_nav_msgs.msg.HingeCarNavAction)
  40. # Waits until the action server has started up and started
  41. # listening for goals.
  42. p0=geometry_msgs.msg.Point()
  43. p00=geometry_msgs.msg.Point()
  44. p1=geometry_msgs.msg.Point()
  45. p2=geometry_msgs.msg.Point()
  46. p3=geometry_msgs.msg.Point()
  47. p4=geometry_msgs.msg.Point()
  48. #in map
  49. # p1.x = 0.0
  50. # p1.y = 0.0
  51. # p2.x = 162.0
  52. # p2.y = 2.5
  53. # p3.x = 162.0
  54. # p3.y = 30.5 #28
  55. # p4.x = 0.0
  56. # p4.y = 28
  57. #in world
  58. #0 base_link in world:181.809424,200.828833,2.987182
  59. #1 base_link in world:15.517689,203.215752,3.130124
  60. #2 base_link in world:15.794460,176.277180,-0.312712
  61. #3 base_link in world:182.272948,171.620984,0.011221
  62. #0 base_link in world:181.809424,200.828833,2.987182
  63. #154.616427,196.909903
  64. p0.x = 173.45 #182.0 qidian
  65. p0.y = 196.3180 #200.0
  66. p00.x = p0.x+2.0 #182.0 zhongdian
  67. p00.y = p0.y #200.0
  68. #184.933232,195.708944
  69. p1.x = 184.93 #182.0
  70. p1.y = 195.7 #
  71. p2.x = 14.45 #15.5 维修
  72. p2.y = 199.64 #203.0
  73. p3.x = 14.81 #15.5
  74. p3.y = 172.2 #175.0 #28
  75. p4.x = 185.08 #182.0
  76. p4.y = 168.3 #172.0 #28
  77. print("before client connected")
  78. client.wait_for_server()
  79. print("client connected")
  80. goal = hinge_car_nav_msgs.msg.HingeCarNavGoal()
  81. path = hinge_car_nav_msgs.msg.HingeCarPath()
  82. tp=[]
  83. goal.goal_type = goal.BACKWARD
  84. # s = hinge_car_nav_msgs.msg.Segment()
  85. # s.segment_type = s.LINE
  86. # start_point = geometry_msgs.msg.Point()
  87. # start_point.x = 0.0
  88. # start_point.y = 0.0
  89. # s.start_point = start_point
  90. # end_point = geometry_msgs.msg.Point()
  91. # end_point.x = 162
  92. # end_point.y = 2.5
  93. # s.end_point = end_point
  94. # s.max_vel = 0.45
  95. # tp.append(s)
  96. # path.target_path.append(s)
  97. s = hinge_car_nav_msgs.msg.Segment()
  98. s.segment_type = s.LINE
  99. # start_point = geometry_msgs.msg.Point()
  100. # start_point.x = -1.5
  101. # start_point.y = -1.2
  102. s.start_point=p0
  103. s.end_point =p2
  104. s.max_vel = -1.0
  105. path.target_path.append(s)
  106. s = hinge_car_nav_msgs.msg.Segment()
  107. s.segment_type = s.CIRCLE
  108. s.start_point=p2
  109. s.end_point =p3
  110. s.center_point.x=0.5*(p2.x+p3.x)
  111. s.center_point.y=0.5*(p2.y+p3.y)
  112. s.max_vel = -0.45
  113. path.target_path.append(s)
  114. s = hinge_car_nav_msgs.msg.Segment()
  115. s.segment_type = s.LINE
  116. s.start_point=p3
  117. s.end_point =p4
  118. s.max_vel = -1.0
  119. path.target_path.append(s)
  120. s = hinge_car_nav_msgs.msg.Segment()
  121. s.segment_type = s.CIRCLE
  122. s.start_point=p4
  123. s.end_point =p1
  124. s.center_point.x=0.5*(p1.x+p4.x)
  125. s.center_point.y=0.5*(p1.y+p4.y)
  126. s.max_vel = -0.45
  127. path.target_path.append(s)
  128. s = hinge_car_nav_msgs.msg.Segment()
  129. s.segment_type = s.LINE
  130. s.start_point=p1
  131. s.end_point =p00
  132. s.max_vel = -1.0
  133. path.target_path.append(s)
  134. # path.target_path=tp
  135. # s = hinge_car_nav_msgs.msg.Segment
  136. # s.segment_type = s.LINE
  137. # s.start_point.x = 1.0
  138. # s.start_point.y = 1.0
  139. # s.end_point.x = 2.0
  140. # s.end_point.y = 2.0
  141. # s.switch_location.swtich_action = s.switch_location.RTK2LIDAR
  142. # s.switch_location.need_swtich_location = True
  143. # q = quaternion_from_euler(0.0, 0, 0.1)
  144. goal.path = path
  145. client.send_goal(goal, done_cb, active_cb, feedback_cb)
  146. # Sends the goal to the action server.
  147. # Waits for the server to finish performing the action.
  148. client.wait_for_result()
  149. client.get_result()
  150. try:
  151. # Initializes a rospy node so that the SimpleActionClient can
  152. # publish and subscribe over ROS.
  153. result = client.get_result()
  154. except rospy.ROSInterruptException:
  155. print("program interrupted before completion")
  156. rospy.sleep(5.0)