imu_data_proc.py 2.7 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061
  1. #!/usr/bin/env python3
  2. # -*- coding: UTF-8 -*-
  3. # Copyright: 2016-2022 https://www.corvin.cn ROS小课堂
  4. # Description: 使用python3从IIC接口中读取IMU模块的三轴线加速度,三轴角速度,四元数原始数据。
  5. # Author: corvin
  6. # History:
  7. # 20220523: Initial this file.
  8. import smbus
  9. import numpy as np
  10. class MyIMUClass(object):
  11. def __init__(self, dev_iic_addr):
  12. self.i2c = smbus.SMBus(1)
  13. self.addr = dev_iic_addr
  14. # 三个数据常量,依次分别代表180.0/32768, 16.0/32768.0, 2000.0/32768.0
  15. self.RPY_CONST = 0.005493164
  16. self.ACC_CONST = 0.000488281
  17. self.ANG_CONST = 0.061035156
  18. # 读取roll,pitch,yaw数据,三轴角速度,三轴线加速度数据
  19. def get_YPRAG(self):
  20. try:
  21. # 读取三轴角度,共计6个字节
  22. rpy_data = self.i2c.read_i2c_block_data(self.addr, 0x3d, 6)
  23. # 读取三轴加速度,共计6个字节
  24. acc_data = self.i2c.read_i2c_block_data(self.addr, 0x34, 6)
  25. # 读取三轴角速度,共计6个字节
  26. ang_data = self.i2c.read_i2c_block_data(self.addr, 0x37, 6)
  27. except IOError:
  28. print("Read IMU RPYAG date error !")
  29. else:
  30. self.raw_roll = float(np.short(np.short(rpy_data[1]<<8)|rpy_data[0])*self.RPY_CONST)
  31. self.raw_pitch = float(np.short(np.short(rpy_data[3]<<8)|rpy_data[2])*self.RPY_CONST)
  32. self.raw_yaw = float(np.short(np.short(rpy_data[5]<<8)|rpy_data[4])*self.RPY_CONST)
  33. self.raw_ax = float(np.short(np.short(acc_data[1]<<8)|acc_data[0])*self.ACC_CONST)
  34. self.raw_ay = float(np.short(np.short(acc_data[3]<<8)|acc_data[2])*self.ACC_CONST)
  35. self.raw_az = float(np.short(np.short(acc_data[5]<<8)|acc_data[4])*self.ACC_CONST)
  36. self.raw_gx = float(np.short(np.short(ang_data[1]<<8)|ang_data[0])*self.ANG_CONST)
  37. self.raw_gy = float(np.short(np.short(ang_data[3]<<8)|ang_data[2])*self.ANG_CONST)
  38. self.raw_gz = float(np.short(np.short(ang_data[5]<<8)|ang_data[4])*self.ANG_CONST)
  39. # 读取四元数,从0x51寄存器连续读取8个字节数据
  40. def get_quatern(self):
  41. try:
  42. quat_data = self.i2c.read_i2c_block_data(self.addr, 0x51, 8)
  43. except IOError:
  44. print("Read IMU quaternion date error !")
  45. else:
  46. self.raw_q0 = float((np.short(np.short(quat_data[1]<<8)|quat_data[0]))/32768.0)
  47. self.raw_q1 = float((np.short(np.short(quat_data[3]<<8)|quat_data[2]))/32768.0)
  48. self.raw_q2 = float((np.short(np.short(quat_data[5]<<8)|quat_data[4]))/32768.0)
  49. self.raw_q3 = float((np.short(np.short(quat_data[7]<<8)|quat_data[6]))/32768.0)