command.py 1.8 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950
  1. #! /usr/bin/env python3
  2. import subprocess
  3. import rospy
  4. import os
  5. file_path = "moveitServer2"
  6. script_directory = os.path.dirname(os.path.abspath(__file__))
  7. import signal
  8. def close_rviz(terminal_name):
  9. # 使用pgrep查找终端进程
  10. pgrep_cmd = "pgrep -f '{}'".format(terminal_name)
  11. pids = subprocess.check_output(pgrep_cmd, shell=True).strip().split()
  12. # 如果找到了匹配的进程ID,发送SIGTERM信号
  13. for pid in pids:
  14. try:
  15. os.kill(int(pid), signal.SIGTERM)
  16. except ProcessLookupError:
  17. pass # 进程可能已经不存在
  18. def load_visual():
  19. command = "rosrun visual visual_node"
  20. subprocess.Popen(['gnome-terminal', '--', 'bash', '-c', command])
  21. def load_rviz():
  22. command = "roslaunch fanuc_m10ia_moveit_config demo.launch"
  23. subprocess.Popen(['gnome-terminal', '--', 'bash', '-c', command])
  24. def launch_publish_pointcloud():
  25. file_name = "dycl_0506.py"
  26. absolute_path = os.path.join(script_directory, file_name)
  27. command = "python3 {}".format(absolute_path)
  28. subprocess.Popen(['gnome-terminal', '--', 'bash', '-c', command])
  29. def launch_moveit_control_server():
  30. file_name = "moveitServer2.py"
  31. absolute_path = os.path.join(script_directory, file_name)
  32. command = "python3 {}".format(absolute_path)
  33. subprocess.Popen(['gnome-terminal', '--', 'bash', '-c', command])
  34. def launch_publish_pointcloud_background():
  35. file_name = "dycl_0506.py"
  36. absolute_path = os.path.join(script_directory, file_name)
  37. command = ["python3", absolute_path]
  38. subprocess.call(command)
  39. def launch_moveit_control_server_background():
  40. file_name = "moveitServer2.py"
  41. absolute_path = os.path.join(script_directory, file_name)
  42. command = ["python3", absolute_path]
  43. subprocess.call(command)