bagtocsv_hmi.py 4.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118
  1. # coding: utf-8
  2. #!/usr/bin/env python2
  3. import os
  4. import rosbag
  5. import csv
  6. import math
  7. import sys
  8. import time
  9. def parsebag(input_dir, output_dir):
  10. dic_object_detection = ['Time','FrameID','HeadingAngle','ID','East', 'North' ,'position_z', 'altitude', 'AbsVel','Type']
  11. object_detection_file = open(output_dir + "/"+"pos_hmi.csv", 'w')
  12. writer_object_detection = csv.writer(object_detection_file)
  13. writer_object_detection.writerow(dic_object_detection)
  14. frame_max=sys.maxsize
  15. with rosbag.Bag(input_dir ,'r') as bag:
  16. #flag=False
  17. framenum = 1
  18. hasLoc = False
  19. for topic,msg,t in bag.read_messages(): #t代表时间
  20. if topic == "/cicv_location":#100hz
  21. hasLoc = True
  22. ego_speed=math.sqrt(msg.velocity_x**2+msg.velocity_y**2+msg.velocity_z**2)
  23. message_location =[str(t)[:-6],framenum,msg.yaw,'-1',msg.position_x,msg.position_y,msg.position_z,msg.altitude,ego_speed,'2']
  24. global pos_x ,pos_y,pos_z
  25. pos_x=msg.position_x
  26. pos_y=msg.position_y
  27. pos_z=msg.position_z
  28. egocar_yaw=msg.yaw
  29. if topic == "/tpperception/hmi": # 10hz
  30. output_type=' '
  31. if not hasLoc :
  32. # print("666")
  33. continue
  34. #global pos_x ,pos_y,pos_z
  35. m=msg.header.sequence_num
  36. if m<frame_max:
  37. frame_max=m
  38. msg_l=len(msg.objs)
  39. #print(msg_l)
  40. #seq=msg.header.sequence_num-frame_max+1
  41. for i in range(msg_l):
  42. obj_x=msg.objs[i].xabs
  43. obj_y=msg.objs[i].yabs
  44. obj_z=msg.objs[i].z+pos_z
  45. # print(msg.objs[i].type)
  46. if msg.objs[i].type==0:
  47. output_type='2' #乘用车/轿车
  48. elif msg.objs[i].type==1:
  49. output_type='4' # 货车/皮卡
  50. elif msg.objs[i].type==2:
  51. output_type='7' #行人
  52. elif msg.objs[i].type==3:
  53. output_type='8' #两轮车
  54. elif msg.objs[i].type==4:
  55. output_type='10' #other
  56. elif msg.objs[i].type==5:
  57. output_type='103' #other
  58. message_obj=[message_location[0], framenum, msg.objs[i].heading, str(msg.objs[i].id), obj_x, obj_y, obj_z,message_location[-3], msg.objs[i].speed, output_type]
  59. writer_object_detection.writerow(message_obj)
  60. writer_object_detection.writerow(message_location)
  61. framenum+=1
  62. #hasLoc = False
  63. #data_read_flag=False
  64. # driving_status_file.close()
  65. object_detection_file.close()
  66. if __name__ == "__main__":
  67. # print("Input the path of file...."+'\n')
  68. input_dir = sys.argv[1]
  69. #input_dir='/media/dell/BFAC-F22B/data/jinlong_datareturn/test_1116/jinlong_data_merge_2023-12-13-05-59-34_TTC_7.bag'
  70. bagname=input_dir.split('/')[-1].split('.')[0]
  71. output_dir = sys.argv[2]
  72. #output_dir='/media/dell/新加卷/bag'
  73. output_dir=os.path.join(output_dir, bagname)
  74. if not os.path.exists(output_dir):
  75. os.makedirs(output_dir)
  76. #parsebag(input_dir, output_dir)
  77. try:
  78. parsebag(input_dir, output_dir)
  79. print('successfully analysis '+input_dir)
  80. except Exception as e:
  81. print(e)
  82. def parse(input_dir, output_dir):
  83. # print("Input the path of file...."+'\n')
  84. #input_dir='/media/dell/BFAC-F22B/data/jinlong_datareturn/test_1116/jinlong_data_merge_2023-12-13-05-59-34_TTC_7.bag'
  85. bagname=input_dir.split('/')[-1].split('.')[0]
  86. #output_dir='/media/dell/新加卷/bag'
  87. output_dir=os.path.join(output_dir, bagname)
  88. if not os.path.exists(output_dir):
  89. os.makedirs(output_dir)
  90. #parsebag(input_dir, output_dir)
  91. try:
  92. parsebag(input_dir, output_dir)
  93. print('successfully analysis '+input_dir)
  94. return output_dir
  95. except Exception as e:
  96. print(e)