imu_6dof_serial.py 5.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183
  1. #!/usr/bin/env python3
  2. # -*- coding: UTF-8 -*-
  3. # Copyright: 2016-2022 https://www.corvin.cn ROS小课堂
  4. # Description: 从串口中读取6DOF IMU模块的三轴加速度、角度、四元数,
  5. # 然后将其打印输出.这里需要注意IMU模块使用的坐标系为ENU东北天坐标系.
  6. # imu模块的串口波特率是固定的57600bps,对于树莓派的串口这里使用的是ttyAMA0,
  7. # 就是排针处的硬件串口,数据通信更为稳定.要想使用该串口需要交换树莓派默认
  8. # 的ttyS0和ttyAMA0,使ttyAMA0为主串口,这里需要先在rasp-config中关闭串口
  9. # 登录功能,启用串口才可以.
  10. # Author: corvin
  11. # History:
  12. # 20220525:Initial this file.
  13. import serial
  14. ACCData = [0.0]*8
  15. GYROData = [0.0]*8
  16. AngleData = [0.0]*8
  17. FrameState = 0 #保存当前数据帧类型
  18. Bytenum = 0 #保存读取到数据帧的第几个字节
  19. CheckSum = 0 #数据帧求和校验位
  20. acc_data = [0.0]*3
  21. angular_data = [0.0]*3
  22. rpy_data = [0.0]*3
  23. # 使用树莓派串口与IMU板进行通信
  24. serial_port="/dev/ttyAMA0"
  25. #对数据进行划分,各自读到对应的数组里
  26. def DueData(inputdata):
  27. #在局部修改全局变量,要进行global的定义
  28. global FrameState
  29. global Bytenum
  30. global CheckSum
  31. global acc_data
  32. global angular_data
  33. global rpy_data
  34. for data in inputdata: #在输入的数据进行遍历
  35. if FrameState == 0: #未读取到数据帧头
  36. if data == 0x55 and Bytenum == 0: #读取到数据帧头,增大bytenum
  37. CheckSum = data
  38. Bytenum = 1
  39. continue
  40. elif data == 0x51 and Bytenum == 1: #在byte不为0 且识别到 0x51的时候,改变frame
  41. CheckSum += data
  42. FrameState = 1
  43. Bytenum = 2
  44. elif data == 0x52 and Bytenum == 1:
  45. CheckSum += data
  46. FrameState = 2
  47. Bytenum = 2
  48. elif data==0x53 and Bytenum==1:
  49. CheckSum+=data
  50. FrameState=3
  51. Bytenum=2
  52. elif FrameState == 1: # acc #已确定数据代表加速度
  53. if Bytenum<10: # 读取8个数据
  54. ACCData[Bytenum-2]=data # 从0开始
  55. CheckSum+=data
  56. Bytenum+=1
  57. else:
  58. if data == (CheckSum&0xff): #假如校验位正确
  59. a = get_acc(ACCData)
  60. print("Acc:", a)
  61. CheckSum = 0 #各数据归零,进行新的循环判断
  62. Bytenum = 0
  63. FrameState = 0
  64. elif FrameState==2: # gyro
  65. if Bytenum<10:
  66. GYROData[Bytenum-2]=data
  67. CheckSum+=data
  68. Bytenum+=1
  69. else:
  70. if data == (CheckSum&0xff):
  71. w = get_gyro(GYROData)
  72. print("Angular:", w)
  73. CheckSum=0
  74. Bytenum=0
  75. FrameState=0
  76. elif FrameState==3: # angle
  77. if Bytenum<10:
  78. AngleData[Bytenum-2]=data
  79. CheckSum+=data
  80. Bytenum+=1
  81. else:
  82. if data == (CheckSum&0xff):
  83. Angle = get_angle(AngleData)
  84. print("Angle(deg):", Angle)
  85. CheckSum=0
  86. Bytenum=0
  87. FrameState=0
  88. def get_acc(datahex):
  89. axl = datahex[0]
  90. axh = datahex[1]
  91. ayl = datahex[2]
  92. ayh = datahex[3]
  93. azl = datahex[4]
  94. azh = datahex[5]
  95. k_acc = 16.0
  96. acc_x = (axh << 8 | axl) / 32768.0 * k_acc
  97. acc_y = (ayh << 8 | ayl) / 32768.0 * k_acc
  98. acc_z = (azh << 8 | azl) / 32768.0 * k_acc
  99. if acc_x >= k_acc:
  100. acc_x -= 2 * k_acc
  101. if acc_y >= k_acc:
  102. acc_y -= 2 * k_acc
  103. if acc_z >= k_acc:
  104. acc_z-= 2 * k_acc
  105. return acc_x,acc_y,acc_z
  106. def get_gyro(datahex):
  107. wxl = datahex[0]
  108. wxh = datahex[1]
  109. wyl = datahex[2]
  110. wyh = datahex[3]
  111. wzl = datahex[4]
  112. wzh = datahex[5]
  113. k_gyro = 2000.0
  114. gyro_x = (wxh << 8 | wxl) / 32768.0 * k_gyro
  115. gyro_y = (wyh << 8 | wyl) / 32768.0 * k_gyro
  116. gyro_z = (wzh << 8 | wzl) / 32768.0 * k_gyro
  117. if gyro_x >= k_gyro:
  118. gyro_x -= 2 * k_gyro
  119. if gyro_y >= k_gyro:
  120. gyro_y -= 2 * k_gyro
  121. if gyro_z >=k_gyro:
  122. gyro_z-= 2 * k_gyro
  123. return gyro_x,gyro_y,gyro_z
  124. def get_angle(datahex):
  125. rxl = datahex[0]
  126. rxh = datahex[1]
  127. ryl = datahex[2]
  128. ryh = datahex[3]
  129. rzl = datahex[4]
  130. rzh = datahex[5]
  131. k_angle = 180.0
  132. angle_x = (rxh << 8 | rxl) / 32768.0 * k_angle
  133. angle_y = (ryh << 8 | ryl) / 32768.0 * k_angle
  134. angle_z = (rzh << 8 | rzl) / 32768.0 * k_angle
  135. if angle_x >= k_angle:
  136. angle_x -= 2 * k_angle
  137. if angle_y >= k_angle:
  138. angle_y -= 2 * k_angle
  139. if angle_z >=k_angle:
  140. angle_z-= 2 * k_angle
  141. return angle_x,angle_y,angle_z
  142. if __name__=='__main__':
  143. # 开启树莓派串口开始获取数据,这里波特率是固定的57600bps
  144. mySerial = serial.Serial(serial_port, 57600, timeout=0.5)
  145. print("Now IMU module is working...")
  146. while True:
  147. # 开始从串口读取44字节数据,共计4帧有效数据进行处理
  148. datahex = mySerial.read(44)
  149. DueData(datahex)