bagtocsv_robot.py 2.7 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788
  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. import numpy as np
  10. def parsebag(input_dir, output_dir):
  11. def quaternion_to_euler(x, y, z, w):
  12. # 将四元数归一化
  13. try:
  14. length = np.sqrt(x**2 + y**2 + z**2 + w**2)
  15. x /= length
  16. y /= length
  17. z /= length
  18. w /= length
  19. # 计算欧拉角
  20. #roll = np.arctan2(2*(w*x + y*z), 1 - 2*(x**2 + y**2))
  21. #pitch = np.arcsin(2*(w*y - z*x))
  22. yaw = np.arctan2(2*(w*z + x*y), 1 - 2*(y**2 + z**2))
  23. return yaw
  24. except :
  25. return 0
  26. dic_object_detection = ['Time','FrameID','HeadingAngle','X', 'Y' ,'Z']
  27. object_detection_file = open(output_dir + "/"+"pos_pji.csv", 'w')
  28. writer_object_detection = csv.writer(object_detection_file)
  29. writer_object_detection.writerow(dic_object_detection)
  30. frame_max=sys.maxsize
  31. with rosbag.Bag(input_dir ,'r') as bag:
  32. #flag=False
  33. framenum = 1
  34. #hasLoc = False
  35. for topic,msg,t in bag.read_messages(): #t代表时间
  36. if topic == "/amcl_pose":#100hz /odom
  37. poseX=msg.pose.pose.position.x
  38. poseY=msg.pose.pose.position.y
  39. poseZ=msg.pose.pose.position.z
  40. orientationX=msg.pose.pose.orientation.x
  41. orientationY=msg.pose.pose.orientation.y
  42. orientationZ=msg.pose.pose.orientation.z
  43. orientationW=msg.pose.pose.orientation.w
  44. egoyaw=quaternion_to_euler(orientationX,orientationY,orientationZ,orientationW)
  45. message_location =[str(t)[:-6],framenum,egoyaw,poseX,poseY,poseZ]
  46. writer_object_detection.writerow(message_location)
  47. framenum+=1
  48. #hasLoc = False
  49. #data_read_flag=False
  50. # driving_status_file.close()
  51. object_detection_file.close()
  52. if __name__ == "__main__":
  53. # print("Input the path of file...."+'\n')
  54. #input_dir = sys.argv[1]
  55. input_dir='/media/dell/BFAC-F22B/data/pujin_datareturn/pjirobot_20231207_2023-12-07-07-18-46_54.bag'
  56. bagname=input_dir.split('/')[-1].split('.')[0]
  57. #output_dir = sys.argv[2]
  58. output_dir='/media/dell/BFAC-F22B/data/pujin_datareturn'
  59. output_dir=os.path.join(output_dir, bagname)
  60. if not os.path.exists(output_dir):
  61. os.makedirs(output_dir)
  62. #parsebag(input_dir, output_dir)
  63. try:
  64. parsebag(input_dir, output_dir)
  65. print('successfully analysis '+input_dir)
  66. except Exception as e:
  67. print(e)