set_update_paramter_p.py 6.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174
  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. import termios
  20. from redis_publisher import Publisher
  21. def wait_for_topic(topic_name, message_type):
  22. try:
  23. message = rospy.wait_for_message(topic_name, message_type, timeout=None)
  24. return message
  25. except rospy.ROSException as e:
  26. rospy.logerr(f"等待话题 {topic_name} 时程序被中断: {e}")
  27. return None
  28. def clear_octomap():
  29. try:
  30. clear_octomap_service = rospy.ServiceProxy('/clear_octomap', Empty) # 创建服务代理
  31. clear_octomap_service() # 尝试调用服务
  32. rospy.loginfo("Octomap has been cleared.")
  33. except rospy.ServiceException as e:
  34. rospy.logerr(f"Failed to call /clear_octomap service or it is not available: {e}. Skipping operation.")
  35. def check_file():
  36. file_path = rospy.get_param("folder_path")
  37. file_path_points = os.path.join(file_path, 'points.txt')
  38. if os.path.exists(file_path_points):
  39. result = True
  40. else:
  41. rospy.loginfo("焊缝数据不存在,请选择焊缝...")
  42. result = False
  43. return result
  44. waited_once = False
  45. tim_list=[]
  46. num = 0
  47. #publisher = Publisher()
  48. if __name__ == "__main__":
  49. command.load_rviz() #启动rviz并在terminal输出相关信息
  50. #command.launch_rviz_background() #启动rviz不在terminal输出信息
  51. rospy.init_node("set_update_paramter_p")
  52. # 初始化各种类型参数
  53. rospy.set_param("cishu",0)
  54. rospy.set_param("time",0)
  55. rospy.set_param("sign_control",0)
  56. rospy.set_param("sign_pointcloud",0)
  57. rospy.set_param("sign_traj_accepted",0)
  58. rospy.set_param("yaw",np.pi/6) #内收角(偏航角)
  59. rospy.set_param("yaw_rate",100) #偏航角过渡速度(角度变化45度/100mm)
  60. rospy.set_param("pitch_of_Horizontalweld",np.pi/4) #和底面夹角(俯仰角)
  61. rospy.set_param("pitch_of_Verticalweld",np.pi/5)
  62. rospy.set_param("culling_radius",0) #焊缝剔除半径
  63. rospy.set_param("folder_path","/home/tong/catkin_ws/data/t_xing") #T型板(1焊缝)
  64. #rospy.set_param("folder_path","/home/tong/moveir_ws/data/6_Welds") #法兰座(6焊缝)
  65. # 显示参数当前值
  66. rospy.loginfo("当前参数值:")
  67. rospy.loginfo("sign_pointcloud = %s", rospy.get_param("sign_pointcloud"))
  68. rospy.loginfo("yaw = %s",rospy.get_param("yaw")/np.pi*180)
  69. rospy.loginfo("pitch_of_Horizontalweld = %s",rospy.get_param("pitch_of_Horizontalweld")/np.pi*180)
  70. rospy.loginfo("pitch_of_Verticalweld = %s",rospy.get_param("pitch_of_Verticalweld")/np.pi*180)
  71. rospy.loginfo("等待rviz启动")
  72. wait_for_topic("/execute_trajectory/status",actionlib_msgs.msg.GoalStatusArray)
  73. while not rospy.is_shutdown():
  74. sign_control = str(rospy.get_param("sign_control"))
  75. if sign_control == "0":
  76. if not waited_once:
  77. print("等待点云数据准备完成...")
  78. # termios.tcflush(sys.stdin, termios.TCIFLUSH) #清空键盘缓冲区
  79. # print("---1.加载点云数据并规划---\n---2.仅重新规划路径---\n---按任意键退出程序---")
  80. # user_input=input("请选择1-2(默认enter为2): ")
  81. # if user_input=="":
  82. # user_input='2'
  83. # rospy.set_param("cishu",rospy.get_param("cishu")+1)
  84. # if(user_input =='1' or user_input=='2'):
  85. # rospy.set_param("sign_control", user_input)
  86. # else:
  87. # command.close_rviz("/usr/bin/python3 /opt/ros/noetic/bin/roslaunch lstrobot_moveit_config_0605 demo.launch")
  88. # sys.exit(0)
  89. waited_once = True
  90. elif sign_control == "1":
  91. flag = check_file()
  92. if flag:
  93. # 重置参数
  94. #rospy.set_param("sign_control",0) #在轨迹规划里重置 防止重复调用
  95. rospy.set_param("sign_traj_accepted",0)
  96. # 清除场景
  97. clear_octomap()
  98. # 点云计算并发布
  99. process = multiprocessing.Process(target=command.launch_publish_pointcloud_background)
  100. process.start()
  101. #计算焊接顺序和焊接姿态
  102. hjsx.run()
  103. hanqiangpose.run()
  104. command.load_visual()
  105. # 等待 /move_group/monitored_planning_scene 话题发布消息
  106. rospy.loginfo("等待场景地图加载完毕...")
  107. wait_for_topic('/move_group/monitored_planning_scene', PlanningScene)
  108. rospy.loginfo("场景地图已加载完毕")
  109. rospy.set_param("sign_pointcloud",1)
  110. #rospy.loginfo("终止点云发布,关闭发布窗口")
  111. #input("按任意键继续...")
  112. rospy.loginfo("运行moveitserver2.py")
  113. process = multiprocessing.Process(target=command.launch_moveit_control_server_background)
  114. process.start()
  115. while rospy.get_param("sign_control"):
  116. pass
  117. #运行结束,重置参数
  118. waited_once = False
  119. else:
  120. rospy.set_param("sign_control",0)
  121. waited_once = False
  122. elif sign_control == "2":
  123. flag = check_file()
  124. if flag:
  125. tim=time.time()
  126. rospy.set_param("time",0)
  127. # 重置参数
  128. #rospy.set_param("sign_control",0)
  129. rospy.set_param("sign_traj_accepted",0)
  130. hjsx.run()
  131. hanqiangpose.run()
  132. command.load_visual()
  133. process = multiprocessing.Process(target=command.launch_moveit_control_server_background)
  134. process.start()
  135. while rospy.get_param("sign_control"):
  136. pass
  137. tim=time.time()-tim
  138. tim_list.append(tim)
  139. num += 1
  140. print("-------------------------------------")
  141. print(f'第{num}次重规划:')
  142. print(tim_list)
  143. print("")
  144. #运行结束,重置参数
  145. waited_once = False
  146. else:
  147. rospy.set_param("sign_control",0)
  148. waited_once = False
  149. else:
  150. rospy.loginfo("正在关闭规划程序...")
  151. command.close_rviz("/usr/bin/python3 /opt/ros/noetic/bin/roslaunch lstrobot_moveit_config_0605 demo.launch")
  152. exit(0)