start.py 4.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134
  1. #! /usr/bin/env python3
  2. import rospy
  3. import os
  4. import hanqiangpose
  5. import command
  6. import subprocess
  7. import hjsx
  8. import threading
  9. import numpy as np
  10. import multiprocessing
  11. from moveit_msgs.msg import PlanningScene
  12. from dynamic_reconfigure.client import Client
  13. from rospy.exceptions import ROSException
  14. from std_srvs.srv import Empty
  15. from rospy.service import ServiceException
  16. import actionlib_msgs.msg._GoalStatusArray
  17. import sys
  18. import time
  19. def wait_for_topic(topic_name, message_type):
  20. try:
  21. message = rospy.wait_for_message(topic_name, message_type, timeout=None)
  22. return message
  23. except rospy.ROSException as e:
  24. rospy.logerr(f"等待话题 {topic_name} 时程序被中断: {e}")
  25. return None
  26. def clear_octomap():
  27. try:
  28. clear_octomap_service = rospy.ServiceProxy('/clear_octomap', Empty) # 创建服务代理
  29. clear_octomap_service() # 尝试调用服务
  30. rospy.loginfo("Octomap has been cleared.")
  31. except ServiceException as e:
  32. rospy.loginfo("Failed to call /clear_octomap service or it is not available. Skipping operation.")
  33. waited_once = False
  34. tim_list=[]
  35. if __name__ == "__main__":
  36. command.load_rviz()
  37. rospy.init_node("start_node")
  38. # 初始化各种类型参数
  39. rospy.set_param("cishu",0)
  40. rospy.set_param("time",0)
  41. rospy.set_param("sign_control",1)
  42. rospy.set_param("sign_pointcloud",0)
  43. rospy.set_param("folder_path","/home/tong/moveir_ws/data/123")
  44. #rospy.set_param("folder_path","/home/tong/moveit_ws/data/renyuan_2")
  45. rospy.loginfo("等待rviz启动")
  46. wait_for_topic("/execute_trajectory/status",actionlib_msgs.msg.GoalStatusArray)
  47. while not rospy.is_shutdown():
  48. sign_control = str(rospy.get_param("sign_control"))
  49. if sign_control == "0":
  50. if not waited_once:
  51. #print("等待点云数据准备完成...")
  52. sys.stdin.flush()#清空键盘缓冲区
  53. aaa=input("请选择 1-2 默认为2: ")
  54. if aaa=="":
  55. aaa='2'
  56. #aaa='2'
  57. rospy.set_param("cishu",rospy.get_param("cishu")+1)
  58. if(aaa =='1' or aaa=='2'):
  59. rospy.set_param("sign_control",aaa)
  60. else:
  61. command.close_rviz("/usr/bin/python3 /opt/ros/noetic/bin/roslaunch fanuc_m10ia_moveit_config demo.launch")
  62. exit(0)
  63. waited_once = True
  64. elif sign_control == "1":
  65. # 重置参数
  66. #rospy.set_param("sign_control",0) #在轨迹规划里重置 防止重复调用
  67. #rospy.set_param("sign_traj_accepted",0)
  68. # 清除场景
  69. clear_octomap()
  70. #点云计算并发布
  71. process = multiprocessing.Process(target=command.launch_publish_pointcloud_background)
  72. process.start()
  73. input("请在rviz中查看点云,然后按回车键继续...")
  74. #计算焊接顺序和焊接姿态
  75. hjsx.run()
  76. hanqiangpose.run()
  77. #time.sleep(10)
  78. command.load_visual()
  79. # 等待 /move_group/monitored_planning_scene 话题发布消息
  80. rospy.loginfo("等待场景地图加载完毕...")
  81. wait_for_topic('/move_group/monitored_planning_scene', PlanningScene)
  82. rospy.loginfo(f"场景地图已加载完毕")
  83. rospy.set_param("sign_pointcloud",1)
  84. #rospy.loginfo("终止点云发布,关闭发布窗口")
  85. rospy.loginfo("运行moveitserver2.py")
  86. process = multiprocessing.Process(target=command.launch_moveit_control_server_background)
  87. process.start()
  88. while rospy.get_param("sign_control"):
  89. pass
  90. #运行结束,重置参数
  91. waited_once = False
  92. elif sign_control == "2":
  93. tim=time.time()
  94. rospy.set_param("time",0)
  95. # 重置参数
  96. #rospy.set_param("sign_control",0)
  97. #rospy.set_param("sign_traj_accepted",0)
  98. hjsx.run()
  99. hanqiangpose.run()
  100. command.load_visual()
  101. process = multiprocessing.Process(target=command.launch_moveit_control_server_background)
  102. process.start()
  103. while rospy.get_param("sign_control"):
  104. pass
  105. # tim=time.time()-tim
  106. # tim_list.append(tim)
  107. # print("-------------------------------------")
  108. # print(f'第{rospy.get_param("cishu")}次规划:')
  109. # print(tim_list)
  110. # print("")
  111. #运行结束,重置参数
  112. waited_once = False