rosbag_record_bak.py 3.0 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576
  1. #!/usr/bin/env python
  2. # -*- coding: utf-8 -*-
  3. import rospy
  4. import rosbag
  5. import sys
  6. import os
  7. import signal
  8. import subprocess
  9. from geometry_msgs.msg import PoseWithCovarianceStamped, Twist
  10. from move_base_msgs.msg import MoveBaseActionGoal
  11. class RosbagRecorder:
  12. def __init__(self, path):
  13. rospy.init_node('rosbag_recorder', anonymous=True)
  14. self.goal_sub = rospy.Subscriber('/move_base/goal', MoveBaseActionGoal, self.goal_callback)
  15. self.pose_sub = rospy.Subscriber('/amcl_pose', PoseWithCovarianceStamped, self.pose_callback)
  16. self.cmd_vel_sub = rospy.Subscriber('/cmd_vel', Twist, self.cmd_vel_callback)
  17. self.goal_position = None
  18. self.bag_process = None
  19. self.recording = False
  20. self.pose_position = None
  21. self.cmd_vel = None
  22. self.bag_path = path
  23. def goal_callback(self, msg):
  24. self.goal_position = msg.goal.target_pose.pose.position
  25. rospy.loginfo("Goal received, starting rosbag recording...")
  26. self.start_recording()
  27. def pose_callback(self, msg):
  28. self.pose_position = msg.pose.pose.position
  29. self.check_stop_condition()
  30. def cmd_vel_callback(self, msg):
  31. self.cmd_vel = msg
  32. self.check_stop_condition()
  33. def start_recording(self):
  34. if not self.recording:
  35. # self.bag_process = subprocess.Popen(['rosbag', 'record', '/amcl_pose', '/cmd_vel', '/some_topic1', '/some_topic2'])
  36. self.bag_process = subprocess.Popen(['rosbag', 'record', '-o', self.bag_path, '/imu', '/obstacle_detection', '/odom', '/sys_info'], preexec_fn=os.setsid)
  37. self.recording = True
  38. def stop_recording(self):
  39. if self.recording and self.bag_process:
  40. rospy.loginfo("Stopping rosbag recording...")
  41. # self.bag_process.terminate()
  42. # self.bag_process.wait()
  43. os.killpg(os.getpgid(self.bag_process.pid), signal.SIGTERM) # 首先发送SIGTERM信号
  44. try:
  45. self.bag_process.wait(timeout=2) # 等待进程终止,如果超过5秒,进行强制终止
  46. except subprocess.TimeoutExpired:
  47. rospy.logwarn("Rosbag process did not terminate, sending SIGKILL...")
  48. os.killpg(os.getpgid(self.bag_process.pid), signal.SIGKILL) # 强制终止
  49. self.bag_process.wait() # 再次等待确保进程已经被终止
  50. self.recording = False
  51. def check_stop_condition(self):
  52. if self.goal_position and self.pose_position and self.cmd_vel:
  53. distance = self.calculate_distance(self.pose_position, self.goal_position)
  54. if distance < 0.3 and self.cmd_vel.linear.x == 0 and self.cmd_vel.linear.y == 0:
  55. self.stop_recording()
  56. def calculate_distance(self, pos1, pos2):
  57. return ((pos1.x - pos2.x) ** 2 + (pos1.y - pos2.y) ** 2) ** 0.5
  58. if __name__ == '__main__':
  59. try:
  60. bag_path = sys.argv[1]
  61. recorder = RosbagRecorder(bag_path)
  62. rospy.spin()
  63. except rospy.ROSInterruptException:
  64. pass