Преглед изворни кода

修改python代码通过iic读取imu模块数据,需要使用np.short进行数据类型转换才能使用

corvin пре 4 година
родитељ
комит
4d2757fb64
1 измењених фајлова са 15 додато и 11 уклоњено
  1. 15 11
      src/rasp_imu_hat_6dof/rasp_imu_hat_6dof/nodes/imu_data.py

+ 15 - 11
src/rasp_imu_hat_6dof/rasp_imu_hat_6dof/nodes/imu_data.py

@@ -5,10 +5,11 @@
 # Author: corvin
 # Description: 为树莓派IMU扩展板所使用的配套代码,由于默认
 #    扩展板与树莓派使用IIC连接。所以这里的代码是直接从IIC接口
-#    中读取IMU模块的三轴加速度、角度、四元数。
+#    中读取IMU模块的三轴加速度、三轴度、四元数。
 # History:
 #    20191031: Initial this file.
-#    20191209: Add get imu chip temperature function-get_temp().
+#    20191209:Add get imu chip temperature function-get_temp().
+#    20200702: 读取各数据后需要使用np.short转换才能进行后续数据处理.
 import smbus
 import rospy
 import numpy as np
@@ -27,9 +28,9 @@ class MyIMU(object):
             ax_tmp  = self.i2c.read_i2c_block_data(self.addr, 0x34, 2)
             ay_tmp  = self.i2c.read_i2c_block_data(self.addr, 0x35, 2)
             az_tmp  = self.i2c.read_i2c_block_data(self.addr, 0x36, 2)
-            #rospy.loginfo("Read accX:" + str(ax_tmp))
-            #rospy.loginfo("Read accY:" + str(ay_tmp))
-            #rospy.loginfo("Read accZ:" + str(az_tmp))
+            #rospy.loginfo("Read i2c accX:" + str(ax_tmp))
+            #rospy.loginfo("Read i2c accY:" + str(ay_tmp))
+            #rospy.loginfo("Read i2c accZ:" + str(az_tmp))
 
             gx_tmp  = self.i2c.read_i2c_block_data(self.addr, 0x37, 2)
             gy_tmp  = self.i2c.read_i2c_block_data(self.addr, 0x38, 2)
@@ -41,13 +42,16 @@ class MyIMU(object):
             self.raw_pitch = float(((pitch_tmp[1]<<8)|pitch_tmp[0])/32768.0*180.0)
             self.raw_yaw  = (yaw_tmp[1] << 8 | yaw_tmp[0])/32768.0*180
 
-            self.raw_ax  = float(((ax_tmp[1]<<8)|ax_tmp[0])/32768.0*16.0)
-            self.raw_ay  = float(((ay_tmp[1]<<8)|ay_tmp[0])/32768.0*16.0)
-            self.raw_az  = float(((az_tmp[1]<<8)|az_tmp[0])/32768.0*16.0)
+            self.raw_ax = float(np.short(np.short(ax_tmp[1]<<8)|ax_tmp[0])/32768.0*16.0)
+            self.raw_ay = float(np.short(np.short(ay_tmp[1]<<8)|ay_tmp[0])/32768.0*16.0)
+            self.raw_az = float(np.short(np.short(az_tmp[1]<<8)|az_tmp[0])/32768.0*16.0)
+            #rospy.loginfo("Read raw accX:" + str(self.raw_ax))
+            #rospy.loginfo("Read raw accY:" + str(self.raw_ay))
+            #rospy.loginfo("Read raw accZ:" + str(self.raw_az))
 
-            self.raw_gx  = float(((gx_tmp[1]<<8)|gx_tmp[0])/32768.0*2000.0)
-            self.raw_gy  = float(((gy_tmp[1]<<8)|gy_tmp[0])/32768.0*2000.0)
-            self.raw_gz  = float(((gz_tmp[1]<<8)|gz_tmp[0])/32768.0*2000.0)
+            self.raw_gx = float(np.short(np.short(gx_tmp[1]<<8)|gx_tmp[0])/32768.0*2000.0)
+            self.raw_gy = float(np.short(np.short(gy_tmp[1]<<8)|gy_tmp[0])/32768.0*2000.0)
+            self.raw_gz = float(np.short(np.short(gz_tmp[1]<<8)|gz_tmp[0])/32768.0*2000.0)
 
     def get_quatern(self):
         try: