Forums - IMU erroneous reading.

5 posts / 0 new
Last post
IMU erroneous reading.
deloney21
Join Date: 29 Mar 19
Posts: 5
Posted: Wed, 2019-04-03 21:10

Hi,

I recently started working on an old Snapdragon Flight. I installed 3.1.3.1 firmware and add on. Running the imu_app and sensor_imu_tester yielded erroneious readings. Specifically, I am seeing high accelerations along 'x' and 'z' axis.  I'm seeing around 7 m/s2 and 13 m/s2 accelerations along 'x' and 'z' axis respectively. Is this expected or I am seeing something faulty.

Abhishek

  • Up0
  • Down0
deloney21
Join Date: 29 Mar 19
Posts: 5
Posted: Wed, 2019-04-03 21:11

[08500/03]  14:07.096  HAP:63:HAP_debug_v2 weak ref not found, return _rtld_sym_zero@_rtld_objmain  0294  symbol.c
[08500/03]  14:07.096  HAP:63:HAP_debug_v2 weak ref not found, return _rtld_sym_zero@_rtld_objmain  0294  symbol.c
[08500/03]  14:07.096  HAP:63:HAP_debug_v2 weak ref not found, return _rtld_sym_zero@_rtld_objmain  0294  symbol.c
[08500/03]  14:07.096  HAP:63:HAP_debug_v2 weak ref not found, return _rtld_sym_zero@_rtld_objmain  0294  symbol.c
[08500/03]  14:07.097  HAP:63:HAP_debug_v2 weak ref not found, return _rtld_sym_zero@_rtld_objmain  0294  symbol.c
[08500/03]  14:07.097  HAP:63:HAP_debug_v2 weak ref not found, return _rtld_sym_zero@_rtld_objmain  0294  symbol.c
[08500/02]  14:07.097  HAP:63:[InitializeImu]: Using SPI port: 1 string: [/dev/spi-1]  0083  StandaloneImuServer.cpp
[08500/01]  14:07.097  HAP:63:enter mpu9x50_initialize  0350  mpu9x50.c
[08500/01]  14:07.097  HAP:63:mpu9x50 configuration validated  0344  mpu9x50.c
[08500/01]  14:07.097  HAP:63:configurations validated  0358  mpu9x50.c
[08500/01]  14:07.101  HAP:63:Opened SPI device /dev/spi-1  0375  mpu9x50.c
[08500/01]  14:07.201  HAP:63:Reset MPU9250  0381  mpu9x50.c
[08500/01]  14:07.202  HAP:63:Waked up device and enabled 20MHz internal clock  0387  mpu9x50.c
[08500/01]  14:07.202  HAP:63:set 4KB FIFO  0394  mpu9x50.c
[08500/01]  14:07.402  HAP:63:Enabled gyro and accel  0400  mpu9x50.c
[08500/01]  14:07.402  HAP:63:Disabled all INTs  0405  mpu9x50.c
[08500/01]  14:07.402  HAP:63:Disabled FIFO on all sensors  0410  mpu9x50.c
[08500/01]  14:07.403  HAP:63:Disabled FIFO mode, I2C Master and DMP  0415  mpu9x50.c
[08500/01]  14:07.403  HAP:63:Disabled I2C (SPI only mode)  0419  mpu9x50.c
[08500/01]  14:07.403  HAP:63:Reset FIFO  0423  mpu9x50.c
[08500/01]  14:07.418  HAP:63:Detecting MPU6500 / MPU9250 IMU sensor  0590  mpu9x50.c
[08500/01]  14:07.418  HAP:63:MPU9250 sensor detected after 0 retries  0608  mpu9x50.c
[08500/01]  14:07.420  HAP:63:MPU9250 gyro initialized  0660  mpu9x50.c
[08500/01]  14:07.420  HAP:63:Set I2C master clock, WAIT_FOR_ES = 0  0682  mpu9x50.c
[08500/01]  14:07.420  HAP:63:Enabled I2C master mode  0688  mpu9x50.c
[08500/01]  14:07.423  HAP:63:Compass register 0 read returned 72  0865  mpu9x50.c
[08500/01]  14:07.423  HAP:63:MPU9250 compass detected  0693  mpu9x50.c
[08500/01]  14:07.426  HAP:63:Compass register 10 set to 0  0812  mpu9x50.c
[08500/01]  14:07.430  HAP:63:Compass register 10 set to 31  0812  mpu9x50.c
[08500/01]  14:07.432  HAP:63:Compass register 16 read returned 187  0865  mpu9x50.c
[08500/01]  14:07.435  HAP:63:Compass register 17 read returned 187  0865  mpu9x50.c
[08500/01]  14:07.436  HAP:63:Compass register 18 read returned 174  0865  mpu9x50.c
[08500/01]  14:07.440  HAP:63:Compass register 10 set to 0  0812  mpu9x50.c
[08500/01]  14:07.440  HAP:63:compass sensitivity adjustment: 1230 1230 1179  0905  mpu9x50.c
[08500/01]  14:07.441  HAP:63:Set I2C_SLV4_CTRL i2c_mst_dly = 4  0729  mpu9x50.c
[08500/01]  14:07.441  HAP:63:Enabled delayed access on I2C slave 4  0736  mpu9x50.c
[08500/01]  14:07.441  HAP:63:compass initialization succ after 0 retries  0463  mpu9x50.c
[08500/01]  14:07.441  HAP:63:Reading MPU9250 configurations....  0473  mpu9x50.c
[08500/01]  14:07.443  HAP:63:gyro_lpf 184Hz, accel_lpf 184Hz  0525  mpu9x50.c
[08500/01]  14:07.443  HAP:63:gyro 500Hz, accel 500Hz, FIFO 0  0527  mpu9x50.c
[08500/01]  14:07.443  HAP:63:gyro_fsr 2000DPS, accel_fsr 16G  0528  mpu9x50.c
[08500/01]  14:07.443  HAP:63:accel_scaling 4 gyro_scaling 1  0531  mpu9x50.c
[08500/01]  14:07.443  HAP:63:compass enabled: compass_fsr 4915 sample rate 100Hz mag_scaling 1  0536  mpu9x50.c
[08500/01]  14:07.443  HAP:63:mpu9x50_initialize succ  0553  mpu9x50.c
[08500/02]  14:07.445  HAP:63:stack size: 1024  0138  StandaloneImuServer.cpp
[08500/02]  14:07.445  HAP:63:setting the thread stack size to[8192]  0141  StandaloneImuServer.cpp
[08500/02]  14:07.445  HAP:63:mpu9x50_poll_data_main created  0150  StandaloneImuServer.cpp
[08500/02]  14:07.445  HAP:58:IMUServer_PollDataThread id = 2097663  0214  StandaloneImuServer.cpp
[08500/02]  14:07.445  HAP:58:sample period 2000 us  0239  StandaloneImuServer.cpp
[08500/02]  14:09.696  HAP:58:exiting IMUServer_PollDataThread  0315  StandaloneImuServer.cpp
[08500/01]  14:09.696  HAP:63:enter mpu9x50_close  0561  mpu9x50.c
[08500/03]  14:11.520  HAP:4158:HAP_debug_v2 weak ref not found, return _rtld_sym_zero@_rtld_objmain  0294  symbol.c
[08500/03]  14:11.520  HAP:4158:HAP_debug_v2 weak ref not found, return _rtld_sym_zero@_rtld_objmain  0294  symbol.c
[08500/03]  14:11.520  HAP:4158:HAP_debug_v2 weak ref not found, return _rtld_sym_zero@_rtld_objmain  0294  symbol.c
[08500/03]  14:11.520  HAP:4158:HAP_debug_v2 weak ref not found, return _rtld_sym_zero@_rtld_objmain  0294  symbol.c
[08500/03]  14:11.520  HAP:4158:HAP_debug_v2 weak ref not found, return _rtld_sym_zero@_rtld_objmain  0294  symbol.c
[08500/03]  14:11.521  HAP:4158:HAP_debug_v2 weak ref not found, return _rtld_sym_zero@_rtld_objmain  0294  symbol.c
[08500/02]  14:11.521  HAP:4158:[InitializeImu]: Using SPI port: 1 string: [/dev/spi-1]  0083  StandaloneImuServer.cpp
[08500/01]  14:11.521  HAP:4158:enter mpu9x50_initialize  0350  mpu9x50.c
[08500/01]  14:11.521  HAP:4158:mpu9x50 configuration validated  0344  mpu9x50.c
[08500/01]  14:11.521  HAP:4158:configurations validated  0358  mpu9x50.c
[08500/01]  14:11.525  HAP:4158:Opened SPI device /dev/spi-1  0375  mpu9x50.c
[08500/01]  14:11.625  HAP:4158:Reset MPU9250  0381  mpu9x50.c
[08500/01]  14:11.625  HAP:4158:Waked up device and enabled 20MHz internal clock  0387  mpu9x50.c
[08500/01]  14:11.625  HAP:4158:set 4KB FIFO  0394  mpu9x50.c
[08500/01]  14:11.825  HAP:4158:Enabled gyro and accel  0400  mpu9x50.c
[08500/01]  14:11.825  HAP:4158:Disabled all INTs  0405  mpu9x50.c
[08500/01]  14:11.826  HAP:4158:Disabled FIFO on all sensors  0410  mpu9x50.c
[08500/01]  14:11.826  HAP:4158:Disabled FIFO mode, I2C Master and DMP  0415  mpu9x50.c
[08500/01]  14:11.826  HAP:4158:Disabled I2C (SPI only mode)  0419  mpu9x50.c
[08500/01]  14:11.826  HAP:4158:Reset FIFO  0423  mpu9x50.c
[08500/01]  14:11.841  HAP:4158:Detecting MPU6500 / MPU9250 IMU sensor  0590  mpu9x50.c
[08500/01]  14:11.841  HAP:4158:MPU9250 sensor detected after 0 retries  0608  mpu9x50.c
[08500/01]  14:11.842  HAP:4158:MPU9250 gyro initialized  0660  mpu9x50.c
[08500/01]  14:11.842  HAP:4158:Set I2C master clock, WAIT_FOR_ES = 0  0682  mpu9x50.c
[08500/01]  14:11.842  HAP:4158:Enabled I2C master mode  0688  mpu9x50.c
[08500/01]  14:11.846  HAP:4158:Compass register 0 read returned 72  0865  mpu9x50.c
[08500/01]  14:11.846  HAP:4158:MPU9250 compass detected  0693  mpu9x50.c
[08500/01]  14:11.850  HAP:4158:Compass register 10 set to 0  0812  mpu9x50.c
[08500/01]  14:11.855  HAP:4158:Compass register 10 set to 31  0812  mpu9x50.c
[08500/01]  14:11.857  HAP:4158:Compass register 16 read returned 187  0865  mpu9x50.c
[08500/01]  14:11.860  HAP:4158:Compass register 17 read returned 187  0865  mpu9x50.c
[08500/01]  14:11.862  HAP:4158:Compass register 18 read returned 174  0865  mpu9x50.c
[08500/01]  14:11.865  HAP:4158:Compass register 10 set to 0  0812  mpu9x50.c
[08500/01]  14:11.866  HAP:4158:compass sensitivity adjustment: 1230 1230 1179  0905  mpu9x50.c
[08500/01]  14:11.868  HAP:4158:Set I2C_SLV4_CTRL i2c_mst_dly = 4  0729  mpu9x50.c
[08500/01]  14:11.868  HAP:4158:Enabled delayed access on I2C slave 4  0736  mpu9x50.c
[08500/01]  14:11.868  HAP:4158:compass initialization succ after 0 retries  0463  mpu9x50.c
[08500/01]  14:11.868  HAP:4158:Reading MPU9250 configurations....  0473  mpu9x50.c
[08500/01]  14:11.870  HAP:4158:gyro_lpf 184Hz, accel_lpf 184Hz  0525  mpu9x50.c
[08500/01]  14:11.870  HAP:4158:gyro 500Hz, accel 500Hz, FIFO 0  0527  mpu9x50.c
[08500/01]  14:11.870  HAP:4158:gyro_fsr 2000DPS, accel_fsr 16G  0528  mpu9x50.c
[08500/01]  14:11.870  HAP:4158:accel_scaling 4 gyro_scaling 1  0531  mpu9x50.c
[08500/01]  14:11.870  HAP:4158:compass enabled: compass_fsr 4915 sample rate 100Hz mag_scaling 1  0536  mpu9x50.c
[08500/01]  14:11.870  HAP:4158:mpu9x50_initialize succ  0553  mpu9x50.c
[08500/02]  14:11.870  HAP:4158:stack size: 1024  0138  StandaloneImuServer.cpp
[08500/02]  14:11.870  HAP:4158:setting the thread stack size to[8192]  0141  StandaloneImuServer.cpp
[08500/02]  14:11.870  HAP:4158:mpu9x50_poll_data_main created  0150  StandaloneImuServer.cpp
[08500/02]  14:11.870  HAP:4154:IMUServer_PollDataThread id = 2105855  0214  StandaloneImuServer.cpp
[08500/02]  14:11.870  HAP:4154:sample period 2000 us  0239  StandaloneImuServer.cpp
[08500/02]  14:22.752  HAP:57:[adsp] getting driver configuration   0122  sensor_imu_impl.cpp
 

  • Up0
  • Down0
deloney21
Join Date: 29 Mar 19
Posts: 5
Posted: Wed, 2019-04-03 21:13

Output of sensor_imu_tester:

The apps <--> dsp offset = [1554350279500490522 ](ns) Apps ClockType[CLOCK_REALTIME]
IMU Library Version: sensor-imu-1.2.3[SensorIMU_v2.cpp, 80]
Initialize Now calling rpcmem_init...[SensorIMU_v2.cpp, 84]
Initialize Now calling rpcmem_alloc...[SensorIMU_v2.cpp, 94]
Initialize rpcmem_alloc passed for SensorIMU buffer size(48000) bytes addr(0x26b30)[SensorIMU_v2.cpp, 107]
Initialize rpcmem_alloc passed for SensorIMU buffer(bias compensated) size(48000) bytes addr(0x326b8)[SensorIMU_v2.cpp, 122]
Initialize rpcmem_alloc passed for SensorIMU buffer(attitude rotation matrix) size(80000) bytes addr(0x3e240)[SensorIMU_v2.cpp, 139]
Imu Initialization Successful.  rpcClientHandle: 1The apps <--> dsp offset = [1554350279500425827 ](ns) Apps ClockType[CLOCK_REALTIME]
waiting for Driver Initialization...
Mpu9x50 Driver is initialiazed...
Getting driver_settings....
 MpuDriver Initialized: true
  Sample Rate(hz)        :   500
  Compass Sample Rate(hz):   100
  accel lpf(hz)          :   184
  gyro lpf(hz)           :   184
[main] flight stack is disabled
successfully got the rotation matrix
{[0,0]: 1.000000}, {[0,1]: 0.000000}, {[0,2]: 0.000000},
{[1,0]: 0.000000}, {[1,1]: -1.000000}, {[1,2]: 0.000000},
{[2,0]: 0.000000}, {[2,1]: 0.000000}, {[2,2]: -1.000000},
findClocksOffset dspClock = 862754803229, monotonicClock=1554351142255235522, clockOffset=1554350279500432293
 buffer[0].timestamp is 1554351142254482000 nsec
buffer[0].timestamp is 1554351142254482000 nsec
completed:.. [   0](s)
completed:.. [   1](s)
completed:.. [   2](s)
completed:.. [   3](s)
completed:.. [   4](s)
completed:.. [   5](s)
test completed...
min: (1) max: (3) num_imu_samples: (7862)
[SensorIMU_v2.cpp, 152]
freeing IMU_DataBuffer: 0x26b30
[SensorIMU_v2.cpp, 157]
freeing BiasCompenstedIMU: 0x326b8
[SensorIMU_v2.cpp, 162]
freeing m_AttutudeRotMatrixBuffer: 0x3e240
dsptime: 867598605 imutime: 867598055 delta: 550
 

  • Up0
  • Down0
deloney21
Join Date: 29 Mar 19
Posts: 5
Posted: Wed, 2019-04-03 21:14

Output of IMU txt:

 

sequence_number, timestamp(us), updated_timestamp(us), acc_x, acc_y, acc_z, ang_
x, ang_y, ang_z
5440, 1554351142254482, 862754057, 0.74, -0.04, -1.37, -0.03, 0.74, -0.03
5441, 1554351142256482, 862756057, 0.74, -0.04, -1.37, -0.03, 0.74, -0.03
5442, 1554351142258480, 862758055, 0.74, -0.04, -1.37, -0.03, 0.74, -0.03
5443, 1554351142260482, 862760057, 0.74, -0.04, -1.38, -0.03, 0.75, -0.04
5444, 1554351142262480, 862762055, 0.74, -0.04, -1.37, -0.03, 0.74, -0.04
5445, 1554351142264480, 862764055, 0.73, -0.04, -1.36, -0.03, 0.74, -0.03
5446, 1554351142266480, 862766055, 0.74, -0.04, -1.37, -0.03, 0.74, -0.03
5447, 1554351142268480, 862768055, 0.74, -0.04, -1.38, -0.03, 0.74, -0.03
5448, 1554351142270480, 862770055, 0.74, -0.04, -1.37, -0.03, 0.74, -0.03
5449, 1554351142272480, 862772055, 0.74, -0.04, -1.37, -0.03, 0.75, -0.04
5450, 1554351142274480, 862774055, 0.74, -0.04, -1.37, -0.03, 0.75, -0.04
5451, 1554351142276480, 862776055, 0.74, -0.04, -1.37, -0.03, 0.75, -0.04
5452, 1554351142278480, 862778055, 0.74, -0.04, -1.37, -0.03, 0.75, -0.04
5453, 1554351142280480, 862780055, 0.74, -0.04, -1.37, -0.03, 0.74, -0.03
5454, 1554351142282480, 862782055, 0.74, -0.04, -1.37, -0.03, 0.74, -0.03
5455, 1554351142284480, 862784055, 0.73, -0.04, -1.37, -0.03, 0.74, -0.03
5456, 1554351142286480, 862786055, 0.74, -0.05, -1.37, -0.03, 0.74, -0.03
5457, 1554351142288479, 862788054, 0.74, -0.04, -1.37, -0.03, 0.74, -0.03
5458, 1554351142290480, 862790055, 0.73, -0.04, -1.37, -0.03, 0.74, -0.03
5459, 1554351142292479, 862792054, 0.74, -0.04, -1.37, -0.03, 0.75, -0.03
 

  • Up1
  • Down0
deloney21
Join Date: 29 Mar 19
Posts: 5
Posted: Mon, 2019-04-08 14:30

After searching around and talking to people facing similar issues with the board, it was suggested that this board belonged to the category of faulty boards. How do I get in touch with the Qualcomm sales/hardware team to inquire about a possible replacement ?

 

 

  • Up0
  • Down0
or Register

Opinions expressed in the content posted here are the personal opinions of the original authors, and do not necessarily reflect those of Qualcomm Incorporated or its subsidiaries (“Qualcomm”). The content is provided for informational purposes only and is not meant to be an endorsement or representation by Qualcomm or any other party. This site may also provide links or references to non-Qualcomm sites and resources. Qualcomm makes no representations, warranties, or other commitments whatsoever about any non-Qualcomm sites or third-party resources that may be referenced, accessible from, or linked to this site.