rosbag_record_old.py 4.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115
  1. '''
  2. Description:
  3. Version: 1.0
  4. Autor: Sun Yalun
  5. Date: 2024-09-05 14:53:32
  6. LastEditors: Sun Yalun
  7. LastEditTime: 2024-09-05 15:46:54
  8. '''
  9. #!/usr/bin/env python
  10. # -*- coding: utf-8 -*-
  11. import rospy
  12. import rosbag
  13. import sys
  14. import os
  15. import signal
  16. import subprocess
  17. from geometry_msgs.msg import PoseWithCovarianceStamped, Twist
  18. from move_base_msgs.msg import MoveBaseActionGoal
  19. from datetime import datetime
  20. class RosbagRecorder:
  21. def __init__(self, bag_dir, count):
  22. rospy.init_node('rosbag_recorder', anonymous=True)
  23. rospy.set_param('/use_sim_time', False)
  24. self.goal_sub = rospy.Subscriber('/move_base/goal', MoveBaseActionGoal, self.goal_callback)
  25. self.pose_sub = rospy.Subscriber('/amcl_pose', PoseWithCovarianceStamped, self.pose_callback)
  26. self.cmd_vel_sub = rospy.Subscriber('/cmd_vel', Twist, self.cmd_vel_callback)
  27. self.goal_position = None
  28. self.bag_process = None
  29. self.recording = False
  30. self.pose_position = None
  31. self.cmd_vel = None
  32. self.bag_dir = bag_dir
  33. self.bag_count = 1
  34. self.total_count = int(count)
  35. def goal_callback(self, msg):
  36. # 如果当前已录制的 bag 文件数量大于等于传入的 count 参数,就不再录制
  37. if self.bag_count > self.total_count:
  38. rospy.loginfo("Recording limit reached. Exiting...")
  39. self.shutdown_node()
  40. return
  41. # 更新时间戳为当前时间
  42. msg.header.stamp = rospy.Time.now()
  43. self.goal_position = msg.goal.target_pose.pose.position
  44. rospy.loginfo("Goal received, starting rosbag recording...")
  45. bag_file_name = f"test-{self.bag_count}.bag"
  46. bag_file_path = os.path.join(self.bag_dir, bag_file_name)
  47. self.bag_path = bag_file_path
  48. self.start_recording()
  49. def pose_callback(self, msg):
  50. # 更新时间戳为当前时间
  51. msg.header.stamp = rospy.Time.now()
  52. self.pose_position = msg.pose.pose.position
  53. self.check_stop_condition()
  54. def cmd_vel_callback(self, msg):
  55. # 更新时间戳为当前时间
  56. # msg.header.stamp = rospy.Time.now()
  57. self.cmd_vel = msg
  58. self.check_stop_condition()
  59. def start_recording(self):
  60. if not self.recording:
  61. self.bag_process = subprocess.Popen(['rosbag', 'record', '-O', self.bag_path, '/amcl_pose', '/imu', '/obstacle_detection', '/odom', '/sys_info'], preexec_fn=os.setsid)
  62. self.recording = True
  63. def stop_recording(self):
  64. if self.recording and self.bag_process:
  65. rospy.loginfo("Stopping rosbag recording...")
  66. # os.killpg(os.getpgid(self.bag_process.pid), signal.SIGTERM) # 首先发送SIGTERM信号
  67. os.killpg(os.getpgid(self.bag_process.pid), signal.SIGINT) # 首先发送SIGINT信号
  68. try:
  69. self.bag_process.wait(timeout=10) # 等待进程终止,如果超过10秒,进行强制终止
  70. except subprocess.TimeoutExpired:
  71. rospy.logwarn("Rosbag process did not terminate, sending SIGKILL...")
  72. os.killpg(os.getpgid(self.bag_process.pid), signal.SIGKILL) # 强制终止
  73. self.bag_process.wait() # 再次等待确保进程已经被终止
  74. self.recording = False
  75. self.bag_count += 1
  76. # 如果录制的包数量达到总数,停止整个节点
  77. if self.bag_count > self.total_count:
  78. rospy.loginfo("All recordings completed. Exiting...")
  79. rospy.sleep(2) # 等待一秒,确保rosbag_recorder节点已经退出
  80. self.shutdown_node()
  81. def check_stop_condition(self):
  82. if self.goal_position and self.pose_position and self.cmd_vel:
  83. distance = self.calculate_distance(self.pose_position, self.goal_position)
  84. if distance < 0.3 and self.cmd_vel.linear.x == 0 and self.cmd_vel.linear.y == 0:
  85. self.stop_recording()
  86. def calculate_distance(self, pos1, pos2):
  87. return ((pos1.x - pos2.x) ** 2 + (pos1.y - pos2.y) ** 2) ** 0.5
  88. def shutdown_node(self):
  89. """停止ROS节点和当前进程"""
  90. rospy.loginfo("Shutting down ROS node and killing the process.")
  91. rospy.sleep(2) # 等待2秒,确保rosbag_recorder节点已经退出
  92. rospy.signal_shutdown("Completed all recordings.")
  93. sys.exit(0) # 终止Python脚本
  94. if __name__ == '__main__':
  95. try:
  96. bag_folder_path = sys.argv[1]
  97. count = sys.argv[2]
  98. recorder = RosbagRecorder(bag_folder_path, count)
  99. rospy.spin()
  100. except rospy.ROSInterruptException:
  101. pass