rosbag_record.py 3.5 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485
  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. from datetime import datetime
  12. class RosbagRecorder:
  13. def __init__(self, path):
  14. rospy.init_node('rosbag_recorder', anonymous=True)
  15. rospy.set_param('/use_sim_time', False)
  16. self.goal_sub = rospy.Subscriber('/move_base/goal', MoveBaseActionGoal, self.goal_callback)
  17. self.pose_sub = rospy.Subscriber('/amcl_pose', PoseWithCovarianceStamped, self.pose_callback)
  18. self.cmd_vel_sub = rospy.Subscriber('/cmd_vel', Twist, self.cmd_vel_callback)
  19. self.goal_position = None
  20. self.bag_process = None
  21. self.recording = False
  22. self.pose_position = None
  23. self.cmd_vel = None
  24. self.bag_path = path
  25. def goal_callback(self, msg):
  26. # 更新时间戳为当前时间
  27. msg.header.stamp = rospy.Time.now()
  28. self.goal_position = msg.goal.target_pose.pose.position
  29. rospy.loginfo("Goal received, starting rosbag recording...")
  30. self.start_recording()
  31. def pose_callback(self, msg):
  32. # 更新时间戳为当前时间
  33. msg.header.stamp = rospy.Time.now()
  34. self.pose_position = msg.pose.pose.position
  35. self.check_stop_condition()
  36. def cmd_vel_callback(self, msg):
  37. # 更新时间戳为当前时间
  38. # msg.header.stamp = rospy.Time.now()
  39. self.cmd_vel = msg
  40. self.check_stop_condition()
  41. def start_recording(self):
  42. if not self.recording:
  43. # self.bag_process = subprocess.Popen(['rosbag', 'record', '/amcl_pose', '/cmd_vel', '/some_topic1', '/some_topic2'])
  44. self.bag_process = subprocess.Popen(['rosbag', 'record', '-O', self.bag_path, '/imu', '/obstacle_detection', '/odom', '/sys_info'], preexec_fn=os.setsid)
  45. self.recording = True
  46. def stop_recording(self):
  47. if self.recording and self.bag_process:
  48. rospy.loginfo("Stopping rosbag recording...")
  49. # self.bag_process.terminate()
  50. # self.bag_process.wait(timeout=10)
  51. # os.killpg(os.getpgid(self.bag_process.pid), signal.SIGTERM) # 首先发送SIGTERM信号
  52. os.killpg(os.getpgid(self.bag_process.pid), signal.SIGINT) # 首先发送SIGINT信号
  53. # self.bag_process.wait(timeout=10)
  54. try:
  55. self.bag_process.wait(timeout=5) # 等待进程终止,如果超过5秒,进行强制终止
  56. except subprocess.TimeoutExpired:
  57. rospy.logwarn("Rosbag process did not terminate, sending SIGKILL...")
  58. os.killpg(os.getpgid(self.bag_process.pid), signal.SIGKILL) # 强制终止
  59. self.bag_process.wait() # 再次等待确保进程已经被终止
  60. self.recording = False
  61. def check_stop_condition(self):
  62. if self.goal_position and self.pose_position and self.cmd_vel:
  63. distance = self.calculate_distance(self.pose_position, self.goal_position)
  64. if distance < 0.3 and self.cmd_vel.linear.x == 0 and self.cmd_vel.linear.y == 0:
  65. self.stop_recording()
  66. def calculate_distance(self, pos1, pos2):
  67. return ((pos1.x - pos2.x) ** 2 + (pos1.y - pos2.y) ** 2) ** 0.5
  68. if __name__ == '__main__':
  69. try:
  70. bag_path = sys.argv[1]
  71. recorder = RosbagRecorder(bag_path)
  72. rospy.spin()
  73. except rospy.ROSInterruptException:
  74. pass