pubGoalB.py 4.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169
  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('/move_base/goal',MoveBaseActionGoal, callback)
  35. # goal_pub = rospy.Publisher('/move_base/goal',MoveBaseActionGoal)
  36. # (FibonacciAction) to the constructor.
  37. client = actionlib.SimpleActionClient(
  38. 'hinge_car_nav', hinge_car_nav_msgs.msg.HingeCarNavAction)
  39. # Waits until the action server has started up and started
  40. # listening for goals.
  41. p0 = geometry_msgs.msg.Point()
  42. p00 = geometry_msgs.msg.Point()
  43. p1 = geometry_msgs.msg.Point()
  44. p2 = geometry_msgs.msg.Point()
  45. p3 = geometry_msgs.msg.Point()
  46. p4 = geometry_msgs.msg.Point()
  47. # in map
  48. # p1.x = 0.0
  49. # p1.y = 0.0
  50. # p2.x = 162.0
  51. # p2.y = 2.5
  52. # p3.x = 162.0
  53. # p3.y = 30.5 #28
  54. # p4.x = 0.0
  55. # p4.y = 28
  56. p0.x = 132.64 # 开始点位
  57. p0.y = 197.3
  58. p00.x = p0.x + 5.0 # 终点点位
  59. p00.y = p0.y
  60. p1.x = 180.0 #184.93
  61. p1.y = 195.7
  62. p2.x = 19.45 # 维修间14.45
  63. p2.y = 199.64
  64. p3.x = 19.81
  65. p3.y = 172.2
  66. p4.x = 180.0 #185.08
  67. p4.y = 168.3
  68. print("before client connected")
  69. client.wait_for_server()
  70. print("client connected")
  71. goal = hinge_car_nav_msgs.msg.HingeCarNavGoal()
  72. path = hinge_car_nav_msgs.msg.HingeCarPath()
  73. tp = []
  74. goal.goal_type = goal.BACKWARD
  75. # s = hinge_car_nav_msgs.msg.Segment()
  76. # s.segment_type = s.LINE
  77. # start_point = geometry_msgs.msg.Point()
  78. # start_point.x = 0.0
  79. # start_point.y = 0.0
  80. # s.start_point = start_point
  81. # end_point = geometry_msgs.msg.Point()
  82. # end_point.x = 162
  83. # end_point.y = 2.5
  84. # s.end_point = end_point
  85. # s.max_vel = 0.45
  86. # tp.append(s)
  87. # path.target_path.append(s)
  88. s = hinge_car_nav_msgs.msg.Segment()
  89. s.segment_type = s.LINE
  90. s.start_point = p0
  91. s.end_point = p2
  92. s.max_vel = -0.45
  93. path.target_path.append(s)
  94. s = hinge_car_nav_msgs.msg.Segment()
  95. s.segment_type = s.CIRCLE
  96. s.start_point = p2
  97. s.end_point = p3
  98. s.center_point.x = 0.5 * (p2.x + p3.x)
  99. s.center_point.y = 0.5 * (p2.y + p3.y)
  100. s.max_vel = -0.45
  101. path.target_path.append(s)
  102. s = hinge_car_nav_msgs.msg.Segment()
  103. s.segment_type = s.LINE
  104. s.start_point = p3
  105. s.end_point = p4
  106. s.max_vel = -0.45
  107. path.target_path.append(s)
  108. s = hinge_car_nav_msgs.msg.Segment()
  109. s.segment_type = s.CIRCLE
  110. s.start_point = p4
  111. s.end_point = p1
  112. s.center_point.x = 0.5 * (p1.x + p4.x)
  113. s.center_point.y = 0.5 * (p1.y + p4.y)
  114. s.max_vel = -0.45
  115. path.target_path.append(s)
  116. s = hinge_car_nav_msgs.msg.Segment()
  117. s.segment_type = s.LINE
  118. s.start_point = p1
  119. s.end_point = p00
  120. s.max_vel = -0.45
  121. path.target_path.append(s)
  122. goal.path = path
  123. client.send_goal(goal, done_cb, active_cb, feedback_cb)
  124. # Sends the goal to the action server.
  125. # Waits for the server to finish performing the action.
  126. client.wait_for_result()
  127. client.get_result()
  128. try:
  129. # Initializes a rospy node so that the SimpleActionClient can
  130. # publish and subscribe over ROS.
  131. result = client.get_result()
  132. except rospy.ROSInterruptException:
  133. print("program interrupted before completion")
  134. rospy.sleep(5.0)