rosbag_record.py 7.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190
  1. #!/usr/bin/env python
  2. # -*- coding: utf-8 -*-
  3. import rospy
  4. import os
  5. import signal
  6. import subprocess
  7. import threading
  8. from geometry_msgs.msg import PoseWithCovarianceStamped, Twist
  9. from move_base_msgs.msg import MoveBaseActionGoal
  10. from math import sqrt
  11. import sys
  12. from datetime import datetime
  13. class RosbagRecorder:
  14. def __init__(self, bag_dir, count):
  15. # 初始化ROS节点
  16. rospy.init_node('rosbag_recorder', anonymous=True)
  17. rospy.set_param('/use_sim_time', False)
  18. # 参数初始化
  19. self.bag_dir = bag_dir
  20. self.total_count = int(count)
  21. self.bag_count = 0
  22. self.recording = False
  23. self.goal_position = None
  24. self.pose_position = None
  25. self.cmd_vel = None
  26. self.bag_process = None
  27. # 创建锁,确保线程安全
  28. self.lock = threading.Lock()
  29. # 订阅话题
  30. self.goal_sub = rospy.Subscriber('/move_base/goal', MoveBaseActionGoal, self.goal_callback)
  31. self.pose_sub = rospy.Subscriber('/amcl_pose', PoseWithCovarianceStamped, self.pose_callback)
  32. self.cmd_vel_sub = rospy.Subscriber('/cmd_vel', Twist, self.cmd_vel_callback)
  33. rospy.loginfo("录制脚本初始化完成,等待终点...")
  34. def goal_callback(self, msg):
  35. with self.lock:
  36. if self.bag_count >= self.total_count:
  37. rospy.loginfo("已达到录制数量上限,退出程序。")
  38. self.shutdown_node()
  39. return
  40. if self.recording:
  41. rospy.logwarn("当前正在录制中,等待当前录制完成后再开始新的录制。")
  42. return
  43. # 记录目标位置
  44. self.goal_position = msg.goal.target_pose.pose.position
  45. rospy.loginfo(f"接收到第{self.bag_count + 1}/{self.total_count}个终点,开始录制第{self.bag_count + 1}/{self.total_count}个rosbag。")
  46. # 设置rosbag文件名
  47. msg.header.stamp = rospy.Time.now()
  48. # bag_file_name = f"test{self.bag_count + 1:02d}.bag"
  49. bag_file_name = f"test-{self.bag_count + 1}.bag"
  50. self.bag_name = bag_file_name
  51. bag_file_path = os.path.join(self.bag_dir, bag_file_name)
  52. self.bag_path = bag_file_path
  53. # 开始录制
  54. self.start_recording()
  55. def pose_callback(self, msg):
  56. with self.lock:
  57. # msg.header.stamp = rospy.Time.now()
  58. self.pose_position = msg.pose.pose.position
  59. self.check_stop_condition()
  60. def cmd_vel_callback(self, msg):
  61. with self.lock:
  62. # msg.header.stamp = rospy.Time.now()
  63. self.cmd_vel = msg
  64. self.check_stop_condition()
  65. def check_stop_condition(self):
  66. if not self.recording:
  67. return
  68. if not self.goal_position or not self.pose_position or not self.cmd_vel:
  69. return
  70. # 计算距离
  71. distance = self.calculate_distance(self.pose_position, self.goal_position)
  72. # 判断是否满足停止录制的条件
  73. if distance < 0.3 and self.cmd_vel.linear.x == 0 and self.cmd_vel.linear.y == 0:
  74. rospy.loginfo(f"满足停止录制条件,停止录制第{self.bag_count + 1}个rosbag。")
  75. self.stop_recording()
  76. def calculate_distance(self, pos1, pos2):
  77. return sqrt((pos1.x - pos2.x) ** 2 + (pos1.y - pos2.y) ** 2)
  78. def start_recording(self):
  79. if self.recording:
  80. rospy.logwarn("已经在录制中,不启动新的录制。")
  81. return
  82. # 生成文件名,包含时间戳以避免重名
  83. # timestamp = datetime.now().strftime("%Y-%m-%d-%H-%M-%S")
  84. # bag_file_name = f"test{self.bag_count + 1:02d}_{timestamp}.bag"
  85. # msg.header.stamp = rospy.Time.now()
  86. # bag_file_name = f"test{self.bag_count + 1:02d}.bag"
  87. # bag_file_path = os.path.join(self.bag_dir, bag_file_name)
  88. # # 确保目录存在
  89. # if not os.path.exists(self.bag_dir):
  90. # try:
  91. # os.makedirs(self.bag_dir)
  92. # rospy.loginfo(f"创建目录:{self.bag_dir}")
  93. # except Exception as e:
  94. # rospy.logerr(f"无法创建目录 {self.bag_dir}:{e}")
  95. # self.shutdown_node()
  96. # return
  97. # 启动rosbag录制
  98. try:
  99. self.bag_process = subprocess.Popen(
  100. ['rosbag', 'record', '-O', self.bag_path, '/cmd_vel', '/move_base/goal', '/amcl_pose', '/imu', '/obstacle_detection', '/odom', '/sys_info'],
  101. preexec_fn=os.setsid,
  102. stdout=subprocess.PIPE,
  103. stderr=subprocess.PIPE
  104. )
  105. self.recording = True
  106. rospy.loginfo(f"开始录制rosbag:{self.bag_name}")
  107. except Exception as e:
  108. rospy.logerr(f"启动rosbag录制失败:{e}")
  109. self.recording = False
  110. def stop_recording(self):
  111. if not self.recording or not self.bag_process:
  112. rospy.logwarn("尝试停止录制,但当前没有录制进程。")
  113. return
  114. try:
  115. # 发送SIGTERM信号终止rosbag进程
  116. os.killpg(os.getpgid(self.bag_process.pid), signal.SIGTERM)
  117. rospy.loginfo("发送SIGTERM信号,尝试终止rosbag录制进程。")
  118. # 等待进程终止
  119. self.bag_process.wait(timeout=10)
  120. rospy.loginfo(f"{self.bag_name}录制进程已终止。")
  121. except subprocess.TimeoutExpired:
  122. rospy.logwarn("rosbag录制进程未能在10秒内终止,发送SIGKILL信号强制终止。")
  123. try:
  124. os.killpg(os.getpgid(self.bag_process.pid), signal.SIGKILL)
  125. self.bag_process.wait()
  126. rospy.loginfo("rosbag录制进程已被SIGKILL信号强制终止。")
  127. except Exception as e:
  128. rospy.logerr(f"强制终止rosbag录制进程失败:{e}")
  129. except Exception as e:
  130. rospy.logerr(f"停止rosbag录制进程时出错:{e}")
  131. # 更新状态
  132. self.recording = False
  133. self.bag_count += 1
  134. rospy.loginfo(f"第{self.bag_count}/{self.total_count}个rosbag录制完成。")
  135. # print("bag_count: ", self.bag_count)
  136. # print("total_count: ", self.total_count)
  137. # 检查是否达到录制数量
  138. if self.bag_count >= self.total_count:
  139. # rospy.loginfo("所有rosbag录制完成,退出程序。")
  140. self.shutdown_node()
  141. # rospy.loginfo("所有rosbag录制完成,退出程序。")
  142. else:
  143. rospy.loginfo("等待下一个目标点以开始新的rosbag录制。")
  144. def shutdown_node(self):
  145. rospy.loginfo("所有rosbag录制完成")
  146. # rospy.loginfo("正在关闭ROS节点并退出程序。")
  147. rospy.loginfo("Shutting down ROS node and killing the process.")
  148. rospy.signal_shutdown("完成所有rosbag录制。")
  149. rospy.sleep(1) # 确保所有日志输出
  150. os._exit(0) # 强制退出程序
  151. if __name__ == '__main__':
  152. try:
  153. # if len(sys.argv) != 3:
  154. # print("用法: rosrun your_package your_script.py <bag_directory> <count>")
  155. # sys.exit(1)
  156. bag_folder_path = sys.argv[1]
  157. count = sys.argv[2]
  158. recorder = RosbagRecorder(bag_folder_path, count)
  159. rospy.spin()
  160. except rospy.ROSInterruptException:
  161. pass