Welcome
Username or Email:

Password:


Missing Code




[ ]
[ ]
Online
  • Guests: 14
  • Members: 0
  • Newest Member: omjtest
  • Most ever online: 396
    Guests: 396, Members: 0 on 12 Jan : 12:51
Members Birthdays:
One birthday today, congrats!
gentoo_daemon (42)


Next birthdays
04/21 kilovolt (49)
04/21 wannabegeekTC (49)
04/21 Elijah (33)
Contact
If you need assistance, please send an email to forum at 4hv dot org. To ensure your email is not marked as spam, please include the phrase "4hv help" in the subject line. You can also find assistance via IRC, at irc.shadowworld.net, room #hvcomm.
Support 4hv.org!
Donate:
4hv.org is hosted on a dedicated server. Unfortunately, this server costs and we rely on the help of site members to keep 4hv.org running. Please consider donating. We will place your name on the thanks list and you'll be helping to keep 4hv.org alive and free for everyone. Members whose names appear in red bold have donated recently. Green bold denotes those who have recently donated to keep the server carbon neutral.


Special Thanks To:
  • Aaron Holmes
  • Aaron Wheeler
  • Adam Horden
  • Alan Scrimgeour
  • Andre
  • Andrew Haynes
  • Anonymous000
  • asabase
  • Austin Weil
  • barney
  • Barry
  • Bert Hickman
  • Bill Kukowski
  • Blitzorn
  • Brandon Paradelas
  • Bruce Bowling
  • BubeeMike
  • Byong Park
  • Cesiumsponge
  • Chris F.
  • Chris Hooper
  • Corey Worthington
  • Derek Woodroffe
  • Dalus
  • Dan Strother
  • Daniel Davis
  • Daniel Uhrenholt
  • datasheetarchive
  • Dave Billington
  • Dave Marshall
  • David F.
  • Dennis Rogers
  • drelectrix
  • Dr. John Gudenas
  • Dr. Spark
  • E.TexasTesla
  • eastvoltresearch
  • Eirik Taylor
  • Erik Dyakov
  • Erlend^SE
  • Finn Hammer
  • Firebug24k
  • GalliumMan
  • Gary Peterson
  • George Slade
  • GhostNull
  • Gordon Mcknight
  • Graham Armitage
  • Grant
  • GreySoul
  • Henry H
  • IamSmooth
  • In memory of Leo Powning
  • Jacob Cash
  • James Howells
  • James Pawson
  • Jeff Greenfield
  • Jeff Thomas
  • Jesse Frost
  • Jim Mitchell
  • jlr134
  • Joe Mastroianni
  • John Forcina
  • John Oberg
  • John Willcutt
  • Jon Newcomb
  • klugesmith
  • Leslie Wright
  • Lutz Hoffman
  • Mads Barnkob
  • Martin King
  • Mats Karlsson
  • Matt Gibson
  • Matthew Guidry
  • mbd
  • Michael D'Angelo
  • Mikkel
  • mileswaldron
  • mister_rf
  • Neil Foster
  • Nick de Smith
  • Nick Soroka
  • nicklenorp
  • Nik
  • Norman Stanley
  • Patrick Coleman
  • Paul Brodie
  • Paul Jordan
  • Paul Montgomery
  • Ped
  • Peter Krogen
  • Peter Terren
  • PhilGood
  • Richard Feldman
  • Robert Bush
  • Royce Bailey
  • Scott Fusare
  • Scott Newman
  • smiffy
  • Stella
  • Steven Busic
  • Steve Conner
  • Steve Jones
  • Steve Ward
  • Sulaiman
  • Thomas Coyle
  • Thomas A. Wallace
  • Thomas W
  • Timo
  • Torch
  • Ulf Jonsson
  • vasil
  • Vaxian
  • vladi mazzilli
  • wastehl
  • Weston
  • William Kim
  • William N.
  • William Stehl
  • Wesley Venis
The aforementioned have contributed financially to the continuing triumph of 4hv.org. They are deserving of my most heartfelt thanks.
Forums
4hv.org :: Forums :: Computer Science
« Previous topic | Next topic »   

IMU with AltIMU-10 v4

Move Thread LAN_403
TheMerovingian
Fri Oct 17 2014, 09:09AM
TheMerovingian Registered Member #14 Joined: Thu Feb 02 2006, 01:04PM
Location: Prato/italy
Posts: 383
Recently I'm designing an IMU for a multicopter starting from the basics but I will soon add also altimeter (already implemented) and GPS

The module i use is the AltIMU-10 v4, comprising of:
LSM303D - 3d accelerometer and 3d magnetometer
L3GD20H - 3d electronic rate gyroscope
LPS25H - Pressure sensor for altitude

I already designed all the mathematical routines to handle these data, in particular based on quaternion and vector calculations, along with fast CORDIC-like trigonometry

The communication between the module and the PIC is made by I2C

I'm able to setup, and read correctly the gyroscope (L3GD20H), magnetometer (LSM303D) and the altimeter (LPS25H), but I have no luck with the accelerometer (L3GD20H)

It simply gives random values centered around 24444 (two modules) or 33000 (the other two). The registers are read and written correctly but no meaningful value comes from the accelerometer.... I exclude module malfunction since I tried 4 of them, coming from different sources.

Without the accelerometer I'm unable to correct the gyro drift in the complementary filter....

MEMS communication subroutines:

'****************************************************************
'*  Name    : MEMS-IMU.BAS                                      *
'*  Author  : Jonathan FIlippi                                  *
'*  Notice  : Copyright (c) 2014 CC free license                *
'*          : All Rights Reserved                               *
'*  Date    : 22/9/2014                                         *
'*  Version : 1.0                                               *
'*  Notes   : MEMS I2C communication, RAW data transformation   *
'*          :                                                   *
'****************************************************************


 
'****************************************************************
'***   VARIABLE DECLARATIONS                                  ***
'****************************************************************
 M_w1              var word
 M_w2              var word
 M_s0              var byte
 M_s1              var byte
 M_s2              var byte
 M_b               var byte[6]
 M_l0              var LONG 'signed
 M_l1              var LONG 'signed
 M_Accel_RAW       var WORD[3] 'vector
 M_Magn_RAW        var WORD[3] 'vector
 M_Gyro_RAW        var WORD[3] 'vector
 M_Gyro_RAW_OFFSET var LONG[3] 'vector
 M_Accel           var long[3] 'vector
 M_Magn            var long[3] 'vector
 M_Gyro            var long[3] 'vector
 M_Altimeter_RAW   var LONG
 M_Altimeter       var LONG
 SLAVE_ADDR        var byte
 ADDR              var byte
 VALUE             var byte 
  

 
'****************************************************************
'***   ALIASES                                                ***
'****************************************************************

' SLAVE addresses
 Symbol MEMS_MagnetAccel_R             = %00111011 'SA0 High
 Symbol MEMS_MagnetAccel_W             = %00111010 'SA0 High
 Symbol MEMS_Gyro_R                    = %11010111 'SA0 High
 Symbol MEMS_Gyro_W                    = %11010110 'SA0 High
 Symbol MEMS_Altimeter_R               = %10111011 'SA0 High
 Symbol MEMS_Altimeter_W               = %10111010 'SA0 High
 
' Generic symbols
 Symbol GX                             = 0
 Symbol GY                             = 1
 Symbol GZ                             = 2
 Symbol WHO_AM_I                       = $0F
 
' gyro sub-addresses
 Symbol GYRO_CTRL1                     = $20
 Symbol GYRO_CTRL2                     = $21
 Symbol GYRO_CTRL3                     = $22
 Symbol GYRO_CTRL4                     = $23
 Symbol GYRO_CTRL5                     = $24
 Symbol GYRO_OUT_X_L                   = $28
 Symbol GYRO_OUT_X_H                   = $29
 Symbol GYRO_OUT_Y_L                   = $2A
 Symbol GYRO_OUT_Y_H                   = $2B
 Symbol GYRO_OUT_Z_L                   = $2C
 Symbol GYRO_OUT_Z_H                   = $2D
 Symbol GYRO_LOW_ODR                   = $39 
 
' accel and magnetometer sub-addresses
 Symbol ACCEL_CTRL0                     = $1F
 Symbol ACCEL_CTRL1                     = $20
 Symbol ACCEL_CTRL2                     = $21
 Symbol ACCEL_CTRL3                     = $22
 Symbol ACCEL_CTRL4                     = $23
 Symbol ACCEL_CTRL5                     = $24
 Symbol ACCEL_CTRL6                     = $25
 Symbol ACCEL_CTRL7                     = $26
 Symbol ACCEL_OUT_X_L                   = $28
 Symbol ACCEL_OUT_X_H                   = $29
 Symbol ACCEL_OUT_Y_L                   = $2A
 Symbol ACCEL_OUT_Y_H                   = $2B
 Symbol ACCEL_OUT_Z_L                   = $2C
 Symbol ACCEL_OUT_Z_H                   = $2D
 Symbol MAGN_OUT_X_L                    = $08
 Symbol MAGN_OUT_X_H                    = $09
 Symbol MAGN_OUT_Y_L                    = $0A
 Symbol MAGN_OUT_Y_H                    = $0B
 Symbol MAGN_OUT_Z_L                    = $0C
 Symbol MAGN_OUT_Z_H                    = $0D
 
 ' altimeter sub-addresses
 Symbol ALTIMETER_RES_CONF              = $10
 Symbol ALTIMETER_CTRL1                 = $20
 Symbol ALTIMETER_CTRL2                 = $21
 Symbol ALTIMETER_CTRL3                 = $22
 Symbol ALTIMETER_CTRL4                 = $23
 
 Symbol ALTIMETER_OUT_XL                = $28
 Symbol ALTIMETER_OUT_L                 = $29
 Symbol ALTIMETER_OUT_H                 = $2A
 
 Symbol ALTIMETER_REF_XL                = $08
 Symbol ALTIMETER_REF_L                 = $09
 Symbol ALTIMETER_REF_H                 = $0A
  
 
'gyro configuration 
 Symbol GYRO_SENSITIVITY             = 2294 '0.07 dps/s/LSB
 Symbol GYRO_SENS_DIVIDER            = 1 '0.07 dps/s/LSB
 Symbol GYRO_2SCOMPLEMENT_MAX        = $FFFF
 Symbol GYRO_CTRL1_VALUE             = %00001111 'DR1-DR0 = 00/BW1-BW0 = 00/PD = 1/
                                                 'Zen = 1/Yen = 1/Zen = 1   , data rate 100Hz
 Symbol GYRO_CTRL2_VALUE             = %00100011 'EXTRen = 0/LVRen = 0/HPM1-HPM0 = 00/  'high pass filter normal
                                                 'HPCF3-HPCF0 = 0011      ' 1 Hz High pass filter cut off freq
 Symbol GYRO_CTRL3_VALUE             = %00000000 'INT1-IG = 0/INT1-BOOT = 0/H_LACTIVE = 0/PP_OD = 1
                                                 'INT2_DRDY = 0/INT2_FTH = 0/INT2_ORun = 0/INT2_Empty = 0
 Symbol GYRO_CTRL4_VALUE             = %10100000 'BDU = 1/BLE = 0/FS1-FS0 = 10/IMPen = 0/ST2-ST1 = 00/ SIM = 0 
                                                 '2000 dps full scale
 Symbol GYRO_CTRL5_VALUE             = %00010000 'BOOT = 0/FIFO_EN = 0/StopOnFTH = 0/HPen = 1/IG_Sel1-IGSel0 = 00
                                                 'OUTG_Sel1-OUTGSel0 = 00                                                                                 
 Symbol GYRO_LOW_ODR_VALUE           = %00000000 '-/-/DRDY_HL = 0/-/I2C_dis = 0/SW_RES = 0/LOW_ODR = 0
                                                                                                                                             
'accel & magnetometer configuration 
 Symbol ACCEL_SENSITIVITY             = 3998 '0.122 mG/LSB
 Symbol ACCEL_2SCOMPLEMENT_MAX        = $FFFF
 Symbol MAGN_2SCOMPLEMENT_MAX         = $FFFF
 symbol MAGN_SENSITIVITY              = 5243 ' 0.160 mgauss / LSB

 Symbol ACCEL_CTRL0_VALUE             = %00000000 'BOOT = 0/FIFO_EN = 0/FTH_EN = 0/0/0/HP_Click = 0/HPIS1 = 0/HPIS2 = 0
 Symbol ACCEL_CTRL1_VALUE             = %01101111 'ADDR3-ADDR0 = 0000/DBU = 1/AZEN = 1/AYEN = 1/AXEN = 1
                                                  ' 100 Hz data rate, all channels elabled
 Symbol ACCEL_CTRL2_VALUE             = %00001000 'ABW1-ABW0 = 00/AFS2-AFS0 = 001/0/AST = 0/SIM = 0
                                                  '50 Hz filter bandwith , 4g sensitivity
 Symbol ACCEL_CTRL3_VALUE             = %00000000 'INT1_BOOT = 0/INT1_Click = 0/INT1_IG1 = 0/INT1_IG2 = 0/INT1_IGM = 0
                                                  'INT1_DRDY_M = 0/INT1_DRDY_M = 0/INT1_EMPTY = 0
 Symbol ACCEL_CTRL4_VALUE             = %00000000 'All interrupts disabled
 Symbol ACCEL_CTRL5_VALUE             = %11110100 'TEMP_EN = 1/M_RES1-M_RES0 = 11/M_ODR2-M_ODR0 = 101/ IRQ non latched
                                                  '100Hz magnetometer data rate
 Symbol ACCEL_CTRL6_VALUE             = %00100000 'MFS1-MFS= 10 magnetic full scale set to 4gauss
 Symbol ACCEL_CTRL7_VALUE             = %00000000 'AHPM1-AHPM0 = 00/AFDS = 0/T_ONLY = 0/MLP = 0/MD1-MD0 = 00
                                                                                                                        
                                                                                                                                                                                                                         
 'altimeter configuration 
 Symbol ALTIMETER_SENSITIVITY         = 8 '4096 LSB = 1hPa
 Symbol ALTIMETER_2SCOMPLEMENT_MAX    = $FFFFFF
 
 Symbol ALTIMETER_RES_CONF_VALUE      = %00001111 'Reserved/AVGT1 = 1/AVGT0 = 1/AVGP1 = 1/AVGP0 = 1                                                                                                
 Symbol ALTIMETER_CTRL1_VALUE         = %11000100 'PD = 1 / ODR2-ODR0 = 100 / DIFF_EN = 0 / BDU = 1 / RESET_AZ = 0 / SIM = 0
 Symbol ALTIMETER_CTRL2_VALUE         = %00000000 'BOOT = 0 / FIFO_EN = 0 / WTM_EN = 0 / FIFO_MEAN_DEC = 0 / SWRESET = 0 / AUTO_ZERO = 0 / ONE_SHOT = 0
 Symbol ALTIMETER_CTRL3_VALUE         = %00000000 'INT_H_L = 0 / PP_OD = 0/ Reserved / INT1_S2-INT1_S1 = 00
 Symbol ALTIMETER_CTRL4_VALUE         = %00000000 '0/0/0/0/ P1_EMPTY = 0/ P1_WTM = 0 / P1_Overrun = 0 / P1_DRDY = 0 
 
                                             

' pin assignements
 SYMBOL I2C_DATAPIN                   = PORTB.1    ' data assigned to PORTB.1
 SYMBOL I2C_CLOCKPIN                  = PORTB.0    ' clock assigned to PORTB.0
 
 
'****************************************************************
'***   I/O PORT ASSIGNMENTS                                   ***
'****************************************************************

TRISB.1 = 0
TRISB.0 = 0



 
goto Q_skipmems:

'******************************************************************************
'********** M_READGYRO_RAW -> vector M_Gyro_RAW[WORD]
'********** this subroutine reads the on-board IMU gyroscope
'********** 
'******************************************************************************
M_READGYRO_RAW: 
 
  SLAVE_ADDR = MEMS_Gyro_W 
  ADDR = GYRO_CTRL1
  value = GYRO_CTRL1_VALUE
  gosub M_I2CWRITE:
 
 for M_s1 = 0 to 5 
  SLAVE_ADDR = MEMS_Gyro_R
  ADDR = GYRO_OUT_X_L + M_s1
  gosub M_I2CREAD:
  M_B[M_s1] = VALUE
 next
 
 for M_s1 = 0 to 4 step 2
  M_Gyro_RAW[M_s1>>1] =  M_b[M_s1+1] << 8 | M_b[M_s1]
 next
return

'******************************************************************************
'********** M_READALTIMETER_RAW -> RAM pressure value[LONG]
'********** this subroutine reads the on-board IMU barometric altimeter
'********** 
'******************************************************************************
M_READALTIMETER_RAW: 
 
  SLAVE_ADDR = MEMS_Altimeter_W 
  ADDR = Altimeter_CTRL1
  value = Altimeter_CTRL1_VALUE
  gosub M_I2CWRITE:
 
 for M_s1 = 0 to 2 
  SLAVE_ADDR = MEMS_Altimeter_R
  ADDR = Altimeter_OUT_XL + M_s1
  gosub M_I2CREAD:
  M_B[M_s1] = VALUE
 next
 
  M_Altimeter_Raw = ((M_B[2] << 8 + M_B[1]) << 8) + M_B[0]

return

'******************************************************************************
'********** M_READALTIMETER -> pressure value[LONG] (hPa)
'********** this subroutine reads the on-board IMU barometric altimeter
'********** 
'******************************************************************************
M_READALTIMETER: 
  
 gosub M_READALTIMETER_RAW:
   
  if M_Gyro_RAW[M_s1] > altimeter_2SCOMPLEMENT_MAX >> 1 then ' sign negative  2's complement value  
   M_l1 = (altimeter_2SCOMPLEMENT_MAX - M_altimeter_RAW) * ALTIMETER_SENSITIVITY      
  else
   M_l1 = M_Altimeter_Raw * ALTIMETER_SENSITIVITY   
  endif
 
 
 'average of 16 values
 if m_altimeter = 0 then
  M_Altimeter = M_l1
 else
  M_Altimeter = ( M_Altimeter << 4  - M_Altimeter + M_l1 ) >> 4
 endif
 
return


'******************************************************************************
'********** M_READGYRO -> vector M_Gyro[LONG] , angle rate in mdegrees/s
'********** this subroutine reads the on-board IMU gyroscope
'********** 
'******************************************************************************
M_READGYRO: 
  
 gosub M_READGYRO_RAW:
   
 for M_s1 = 0 to 2 
   if M_Gyro_RAW[M_s1] > GYRO_2SCOMPLEMENT_MAX >> 1 then ' sign negative  2's complement value  
   M_Gyro[M_s1] = (-(GYRO_2SCOMPLEMENT_MAX - M_Gyro_RAW[M_s1]) - M_Gyro_RAW_OFFSET[M_s1]) * GYRO_SENSITIVITY / GYRO_SENS_DIVIDER    
  else
   M_Gyro[M_s1] = (M_Gyro_RAW[M_s1] - M_Gyro_RAW_OFFSET[M_s1]) * GYRO_SENSITIVITY / GYRO_SENS_DIVIDER    
  endif
 next

return


'******************************************************************************
'********** M_CONFIGGYRO 
'********** configurates the Gyroscope device
'********** 
'******************************************************************************
M_CONFIGGYRO: 

  SLAVE_ADDR = MEMS_Gyro_W
  
  ADDR = GYRO_CTRL1
  value = GYRO_CTRL1_VALUE
  gosub M_I2CWRITE:
  
  ADDR = GYRO_CTRL2
  value = GYRO_CTRL2_VALUE
  gosub M_I2CWRITE:
  
  ADDR = GYRO_CTRL3
  value = GYRO_CTRL3_VALUE
  gosub M_I2CWRITE:
 
  ADDR = GYRO_CTRL4
  value = GYRO_CTRL4_VALUE
  gosub M_I2CWRITE:
  
  ADDR = GYRO_CTRL5
  value = GYRO_CTRL5_VALUE
  gosub M_I2CWRITE:
  
  ADDR = GYRO_LOW_ODR
  value = GYRO_LOW_ODR_VALUE
  gosub M_I2CWRITE:
  
  gosub M_READGYRO:
  
return

'******************************************************************************
'********** M_CONFIGALTIMETER
'********** configurates the barometric altimeter
'********** 
'******************************************************************************
M_CONFIGALTIMETER: 

  SLAVE_ADDR = MEMS_ALTIMETER_W
  
  ADDR = ALTIMETER_CTRL1
  value = ALTIMETER_CTRL1_VALUE
  gosub M_I2CWRITE:
  
  ADDR = ALTIMETER_CTRL2
  value = ALTIMETER_CTRL2_VALUE
  gosub M_I2CWRITE:
  
  SLAVE_ADDR = MEMS_ALTIMETER_R
  ADDR = ALTIMETER_RES_CONF
  gosub M_I2CREAD:
  
  M_s1 = value >> 4
  VALUE = M_s1 << 4 + ALTIMETER_RES_CONF_VALUE
  
  SLAVE_ADDR = MEMS_ALTIMETER_W
  ADDR = ALTIMETER_RES_CONF
  gosub M_I2CWRITE:
  
  M_Altimeter = 0 
  
return


'******************************************************************************
'********** M_CONFIGGYRO 
'********** calculates the gyroscope offset
'********** 
'******************************************************************************
 
M_CONFIGGYROOFFSET: 
   ' offset calibration
  
  for M_s0 = 0 to 2
   M_Gyro_RAW_OFFSET[M_s0] = 0
   for M_s2 = 0 to $FF
    gosub M_READGYRO_RAW:
    M_Gyro_RAW_OFFSET[M_s0] = M_Gyro_RAW_OFFSET[M_s0] + M_Gyro_RAW[M_s0] 
    pause 2
   next M_s2 
   M_Gyro_RAW_OFFSET[M_s0] = M_Gyro_RAW_OFFSET[M_s0] >> 8
  if M_Gyro_RAW_OFFSET[M_s0] > GYRO_2SCOMPLEMENT_MAX >> 1 then ' sign negative  2's complement value  
   M_Gyro_RAW_OFFSET[M_s0] = -(GYRO_2SCOMPLEMENT_MAX - M_Gyro_RAW[M_s0])   
  else
   M_Gyro_RAW_OFFSET[M_s0] = (M_Gyro_RAW[M_s0] )  
  endif
  next M_s0


return


'******************************************************************************
'********** M_READACCEL_RAW -> vector M_Accel_RAW[WORD]
'********** this subroutine reads the on-board IMU accelerometer
'********** 
'******************************************************************************
M_READACCEL_RAW: 
 
  'SLAVE_ADDR = MEMS_MagnetAccel_W 
 ' ADDR = ACCEL_CTRL0
  'value = ACCEL_CTRL0_VALUE
  'gosub M_I2CWRITE:
 
 for M_s1 = 0 to 5 
  SLAVE_ADDR = MEMS_MagnetAccel_R
  ADDR = ACCEL_OUT_X_L + M_s1
  gosub M_I2CREAD:
  M_B[M_s1] = VALUE
 next
 
 for M_s1 = 0 to 4 step 2
  M_Accel_RAW[M_s1>>1] = M_b[M_s1+1] << 8 | M_b[M_s1] 
 next
return


'******************************************************************************
'********** M_READACCEL -> vector M_Accel[LONG] , acceleration in g
'********** this subroutine reads the on-board IMU accelerometer
'********** 
'******************************************************************************
M_READACCEL:


 gosub M_READACCEL_RAW:
   
 for M_s1 = 0 to 2 
   if M_Accel_RAW[M_s1] > ACCEL_2SCOMPLEMENT_MAX >> 1 then ' sign negative  2's complement value  
   M_Accel[M_s1] = -(ACCEL_2SCOMPLEMENT_MAX - M_Accel_RAW[M_s1])  * ACCEL_SENSITIVITY   
  else
   M_Accel[M_s1] = M_Accel_RAW[M_s1] * ACCEL_SENSITIVITY 
  endif
 next

return
                
'******************************************************************************
'********** M_READMAGN_RAW -> vector M_Magn_RAW[WORD]
'********** this subroutine reads the on-board IMU accelerometer
'********** 
'******************************************************************************
M_READMAGN_RAW: 
 

 
  SLAVE_ADDR = MEMS_MagnetAccel_W 
  ADDR = ACCEL_CTRL0
  value = ACCEL_CTRL0_VALUE
  gosub M_I2CWRITE:
 
 for M_s1 = 0 to 5 
  SLAVE_ADDR = MEMS_MagnetAccel_R
  ADDR = MAGN_OUT_X_L + M_s1
  gosub M_I2CREAD:
  M_B[M_s1] = VALUE
 next
 
 for M_s1 = 0 to 4 step 2
  M_MAgn_RAW[M_s1/2] = M_b[M_s1+1] << 8 | M_b[M_s1] 
 next
return
                
                
    
                
'******************************************************************************
'********** M_READMAGN -> vector M_Magn[LONG] , magnetic axes in gauss
'********** this subroutine reads the on-board IMU accelerometer
'********** 
'******************************************************************************
M_READMAGN:


 gosub M_READMAGN_RAW:
   
 for M_s1 = 0 to 2 
   if M_Magn_RAW[M_s1] > 32768 then ' sign negative  2's complement value  
   M_Magn[M_s1] = -(MAGN_2SCOMPLEMENT_MAX - M_MAGN_RAW[M_s1])  * MAGN_SENSITIVITY   
  else
   M_Magn[M_s1] = M_Magn_RAW[M_s1] * MAGN_SENSITIVITY 
  endif
 next

return

'******************************************************************************
'********** M_CONFIGACCELMAGN
'********** configurates the Accelerometer & Magnetometer device
'********** 
'******************************************************************************
M_CONFIGACCELMAGN: 
       
  SLAVE_ADDR = MEMS_MagnetAccel_W
  
  ADDR = ACCEL_CTRL0
  value = ACCEL_CTRL0_VALUE
  gosub M_I2CWRITE:
  
  ADDR = ACCEL_CTRL1
  value = ACCEL_CTRL1_VALUE
  gosub M_I2CWRITE:        
  
  ADDR = ACCEL_CTRL2
  value = ACCEL_CTRL2_VALUE
  gosub M_I2CWRITE:      
  
  ADDR = ACCEL_CTRL3
  value = ACCEL_CTRL3_VALUE
  gosub M_I2CWRITE: 
            
  ADDR = ACCEL_CTRL4
  value = ACCEL_CTRL4_VALUE
  gosub M_I2CWRITE: 
  
  ADDR = ACCEL_CTRL5
  value = ACCEL_CTRL5_VALUE
  gosub M_I2CWRITE:  
  
  ADDR = ACCEL_CTRL6
  value = ACCEL_CTRL6_VALUE
  gosub M_I2CWRITE: 
  
  ADDR = ACCEL_CTRL7
  value = ACCEL_CTRL7_VALUE
  gosub M_I2CWRITE:         

return

'******************************************************************************
'********** M_I2CWRITE
'********** This function writes a byte VALUE into ADDR at the SLAVE_ADDR
'********** 
'******************************************************************************
M_I2CWRITE: 
       
 I2CWRITE I2C_DATAPIN,I2C_CLOCKPIN,SLAVE_ADDR,ADDR,[VALUE]
 
return

'******************************************************************************
'********** M_I2CREAD
'********** This function writes a byte VALUE into ADDR at the SLAVE_ADDR
'********** 
'******************************************************************************
M_I2CREAD: 
       
 I2CREAD I2C_DATAPIN,I2C_CLOCKPIN,SLAVE_ADDR,ADDR,[VALUE]
 
return

Q_skipmems:

I didn't include the mathematical subroutines since they aren't used yet.

Back to top
Dave47
Tue Oct 28 2014, 12:12AM
Dave47 Registered Member #84 Joined: Thu Feb 09 2006, 01:06PM
Location: Dallas, TX
Posts: 47
I have the AltIMU-10 v3 and everything works fine with example program that Pololu provides. Maybe you can use it to verify that your board actually works?

In my application, I used a Teensy 3.0 to log the data to an SD card for my model rocket.

David

Back to top
Patrick
Wed Oct 29 2014, 07:59AM
Patrick Registered Member #2431 Joined: Tue Oct 13 2009, 09:47PM
Location: Chico, CA. USA
Posts: 5639
Im so interested in things like this, i even bought some real good accel, gyros, and mags. i just wish i new more about I2C and SPI, i even have a I2C LiDAR.
Back to top
TheMerovingian
Tue Jan 20 2015, 09:39AM
TheMerovingian Registered Member #14 Joined: Thu Feb 02 2006, 01:04PM
Location: Prato/italy
Posts: 383
ACtually I have finished the AHRS part (10-DOF) including the filtering of the gyro data with accelerometer and magnetometer and the determination of global acceleration components to filter the barometric data (it needs some tuning). The filtering is done with a variable gain complementary filter (adjusts the gain depending on how much the accelerometer data is off), i didn't use kalman since it is too slow for this hardware. I have also changed the PIC18f2680 to a PIC18F26k80 running at 64 MHz and moved the I2C bus on the hardware bus increasing the clock frequency to 1MHz, obtaining an imu update rate of 150-180 Hz.

Actually i'm working on the GPS part. I'm able to read it at 10Hz rate but it is very difficult to sinch with the IMU (since there are no background processes in those type of PIC). I want to minimize the time the the USART bus (hardware) waits for the NMEA String since it will ruin the IMU update rate greatly, even if the duty cycle is very low (7%). In optimal conditions, the NMEA string reading takes 7ms every 100ms so it needs very careful sinching by using the hardware clock of the PIC (i'm already using TMR1 driven by PIC instruction clock with a 64 prescale value, each LSB corresponds to 4us).

If the GPS falls out of sinch (and it is very likely since there is also some unpredictable duty cycle devoted to printing the data on an LCD screen) the IMU freezes for 100ms that means instant crash for an UAV :D :D :D

I hate USART frown... I2C GPS would be much more useful...

Anyways if the problem cannot be solved I will be forced to add a second PIC to work as a front-end for the GPS, the PPM, D-Bus receiver and the AI, while the core pic will take care only of the IMU and the output to the ESCs taking angle setpoints from the other pic...

Back to top

Moderator(s): Chris Russell, Noelle, Alex, Tesladownunder, Dave Marshall, Dave Billington, Bjørn, Steve Conner, Wolfram, Kizmo, Mads Barnkob

Go to:

Powered by e107 Forum System
 
Legal Information
This site is powered by e107, which is released under the GNU GPL License. All work on this site, except where otherwise noted, is licensed under a Creative Commons Attribution-ShareAlike 2.5 License. By submitting any information to this site, you agree that anything submitted will be so licensed. Please read our Disclaimer and Policies page for information on your rights and responsibilities regarding this site.