pjirebot_evaluate_csv.py 4.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125
  1. #!/usr/bin/env python3
  2. # -*- coding: utf-8 -*-
  3. """
  4. Created on Mon Dec 25 17:35:56 2023
  5. @author: dell
  6. """
  7. # coding: utf-8
  8. # !/usr/bin/env python2
  9. import os
  10. import rosbag
  11. import csv
  12. import math
  13. import sys
  14. import time
  15. from datetime import datetime
  16. import rospy
  17. def parsebag(input_dir, output_dir):
  18. dic_EgoState = ['Time', 'simTime', 'simFrame', 'posX', 'posY', 'posZ', 'speedX', 'speedY', 'speedZ', 'accelX',
  19. 'accelY', 'accelZ', 'dimX', 'dimY', 'dimZ', 'obstacle', 'traveledDist']
  20. # dic_DriverCtrl=['Time','simTime','simFrame','tarspeedX','tarspeedY','tarspeedZ','tardimX','tardimY','tardimZ']
  21. EgoState_file = open(output_dir + "/" + "EgoState_pji.csv", 'w')
  22. # DriverCtrl_file = open(output_dir + "/"+"DriverCtrl_pji.csv", 'w')
  23. writer_EgoState = csv.writer(EgoState_file)
  24. writer_EgoState.writerow(dic_EgoState)
  25. # writer_DriverCtrl = csv.writer(DriverCtrl_file)
  26. # writer_DriverCtrl.writerow(dic_DriverCtrl)
  27. frame_max = sys.maxsize
  28. count = 1
  29. with rosbag.Bag(input_dir, 'r') as bag:
  30. odom_flag = False
  31. first_message_time = None
  32. Frame_imu = 1
  33. Frame_cmd_vel = 1
  34. obstacle_state = 0
  35. cur_mileage = ''
  36. for topic, msg, t in bag.read_messages(): # t代表时间
  37. if first_message_time is None:
  38. first_message_time = t
  39. first_message_time = rospy.Time.to_sec(first_message_time)
  40. first_message_time = datetime.fromtimestamp(first_message_time)
  41. if topic == "/obstacle_detection":
  42. obstacle_state = msg.data
  43. # print(msg.data)
  44. if topic == "/sys_info":
  45. cur_mileage = msg.cur_mileage
  46. if topic == "/odom":
  47. odom_flag = True
  48. posX = msg.pose.pose.position.x
  49. posY = msg.pose.pose.position.y
  50. posZ = msg.pose.pose.position.z
  51. speedX = msg.twist.twist.linear.x * 3.6
  52. speedY = msg.twist.twist.linear.y * 3.6
  53. speedZ = msg.twist.twist.linear.z * 3.6
  54. dimX = msg.twist.twist.angular.x
  55. dimY = msg.twist.twist.angular.y
  56. dimZ = msg.twist.twist.angular.z
  57. if topic == "/imu":
  58. if odom_flag:
  59. accelX = msg.linear_acceleration.x
  60. accelY = msg.linear_acceleration.y
  61. accelZ = msg.linear_acceleration.z
  62. timestamp = rospy.Time.to_sec(t)
  63. date_time_imu = datetime.fromtimestamp(timestamp)
  64. simtime_imu = (date_time_imu - first_message_time).total_seconds()
  65. message_EgoState = [date_time_imu, simtime_imu, Frame_imu, posX, posY, posZ, speedX, speedY, speedZ,
  66. accelX, accelY, accelZ, dimX, dimY, dimZ, obstacle_state, cur_mileage]
  67. writer_EgoState.writerow(message_EgoState)
  68. Frame_imu += 1
  69. else:
  70. print('6666')
  71. '''
  72. if topic =='/cmd_vel':
  73. timestamp = rospy.Time.to_sec(t)
  74. date_time_cmd_vel = datetime.fromtimestamp(timestamp)
  75. simtime_cmd_vel=(date_time_cmd_vel-first_message_time).total_seconds()
  76. message_DriverCtrl =[date_time_cmd_vel,simtime_cmd_vel,Frame_cmd_vel,msg.linear.x*3.6,msg.linear.y*3.6,msg.linear.z*3.6,
  77. msg.angular.x,msg.angular.y,msg.angular.z]
  78. writer_DriverCtrl.writerow(message_DriverCtrl)
  79. Frame_cmd_vel+=1
  80. '''
  81. EgoState_file.close()
  82. # DriverCtrl_file.close()
  83. if __name__ == "__main__":
  84. # print("Input the path of file...."+'\n')
  85. # input_dir = sys.argv[1]
  86. input_dir = './bag/2024-04-22-08-48-30_obstacledetection_30.bag'
  87. bagname = input_dir.split('/')[-1].split('.')[0]
  88. # output_dir = sys.argv[2]
  89. output_dir = './'
  90. output_dir = os.path.join(output_dir, bagname)
  91. if not os.path.exists(output_dir):
  92. os.makedirs(output_dir)
  93. parsebag(input_dir, output_dir)
  94. '''
  95. try:
  96. parsebag(input_dir, output_dir)
  97. print('successfully analysis '+input_dir)
  98. except Exception as e:
  99. print(e)
  100. '''