Andrew SaLoutos / ICM_20948
Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers ICM_20948_C.h Source File

ICM_20948_C.h

00001 /*
00002 
00003 This is a C-compatible interface to the features presented by the ICM 20948 9-axis device
00004 The imementation of the interface is flexible
00005 
00006 */
00007 
00008 #ifndef _ICM_20948_C_H_
00009 #define _ICM_20948_C_H_
00010 
00011 #include <stdint.h>
00012 #include <stdbool.h>
00013 #include <stddef.h>
00014 
00015 #include "ICM_20948_REGISTERS.h"
00016 #include "ICM_20948_ENUMERATIONS.h" // This is to give users access to usable value definiitons
00017 #include "AK09916_ENUMERATIONS.h"
00018 #include "ICM_20948_DMP.h"
00019 
00020 #ifdef __cplusplus
00021 extern "C"
00022 {
00023 #endif /* __cplusplus */
00024 
00025 extern int memcmp(const void *, const void *, size_t); // Avoid compiler warnings
00026 
00027 // Define if the DMP will be supported
00028 // Note: you must have 14290/14301 Bytes of program memory available to store the DMP firmware!
00029 //#define ICM_20948_USE_DMP // Uncomment this line to enable DMP support. You can of course use ICM_20948_USE_DMP as a compiler flag too
00030 
00031 // There are two versions of the InvenSense DMP firmware for the ICM20948 - with slightly different sizes
00032 #define DMP_CODE_SIZE 14301 /* eMD-SmartMotion-ICM20948-1.1.0-MP */
00033 //#define DMP_CODE_SIZE 14290 /* ICM20948_eMD_nucleo_1.0 */
00034 
00035 
00036 #define ICM_20948_I2C_ADDR_AD0 0x68 // Or 0x69 when AD0 is high
00037 #define ICM_20948_I2C_ADDR_AD1 0x69 //
00038 #define ICM_20948_WHOAMI 0xEA
00039 
00040 #define MAG_AK09916_I2C_ADDR 0x0C
00041 #define MAG_AK09916_WHO_AM_I 0x4809
00042 #define MAG_REG_WHO_AM_I 0x00
00043 
00044 /** @brief Max size that can be read across I2C or SPI data lines */
00045 #define INV_MAX_SERIAL_READ 16
00046 /** @brief Max size that can be written across I2C or SPI data lines */
00047 #define INV_MAX_SERIAL_WRITE 16
00048 
00049   typedef enum
00050   {
00051     ICM_20948_Stat_Ok = 0x00, // The only return code that means all is well
00052     ICM_20948_Stat_Err,       // A general error
00053     ICM_20948_Stat_NotImpl,   // Returned by virtual functions that are not implemented
00054     ICM_20948_Stat_ParamErr,
00055     ICM_20948_Stat_WrongID,
00056     ICM_20948_Stat_InvalSensor, // Tried to apply a function to a sensor that does not support it (e.g. DLPF to the temperature sensor)
00057     ICM_20948_Stat_NoData,
00058     ICM_20948_Stat_SensorNotSupported,
00059     ICM_20948_Stat_DMPNotSupported,    // DMP not supported (no #define ICM_20948_USE_DMP)
00060     ICM_20948_Stat_DMPVerifyFail,      // DMP was written but did not verify correctly
00061     ICM_20948_Stat_FIFONoDataAvail,    // FIFO contains no data
00062     ICM_20948_Stat_FIFOIncompleteData, // FIFO contained incomplete data
00063     ICM_20948_Stat_FIFOMoreDataAvail,  // FIFO contains more data
00064     ICM_20948_Stat_UnrecognisedDMPHeader,
00065     ICM_20948_Stat_UnrecognisedDMPHeader2,
00066     ICM_20948_Stat_InvalDMPRegister, // Invalid DMP Register
00067 
00068     ICM_20948_Stat_NUM,
00069     ICM_20948_Stat_Unknown,
00070   } ICM_20948_Status_e;
00071 
00072   typedef enum
00073   {
00074     ICM_20948_Internal_Acc = (1 << 0),
00075     ICM_20948_Internal_Gyr = (1 << 1),
00076     ICM_20948_Internal_Mag = (1 << 2),
00077     ICM_20948_Internal_Tmp = (1 << 3),
00078     ICM_20948_Internal_Mst = (1 << 4), // I2C Master Ineternal
00079   } ICM_20948_InternalSensorID_bm;     // A bitmask of internal sensor IDs
00080 
00081   typedef union
00082   {
00083     int16_t i16bit[3];
00084     uint8_t u8bit[6];
00085   } ICM_20948_axis3bit16_t;
00086 
00087   typedef union
00088   {
00089     int16_t i16bit;
00090     uint8_t u8bit[2];
00091   } ICM_20948_axis1bit16_t;
00092 
00093   typedef struct
00094   {
00095     uint8_t a : 2;
00096     uint8_t g : 2;
00097     uint8_t reserved_0 : 4;
00098   } ICM_20948_fss_t; // Holds full-scale settings to be able to extract measurements with units
00099 
00100   typedef struct
00101   {
00102     uint8_t a;
00103     uint8_t g;
00104   } ICM_20948_dlpcfg_t; // Holds digital low pass filter settings. Members are type ICM_20948_ACCEL_CONFIG_DLPCFG_e
00105 
00106   typedef struct
00107   {
00108     uint16_t a;
00109     uint8_t g;
00110   } ICM_20948_smplrt_t;
00111 
00112   typedef struct
00113   {
00114     uint8_t I2C_MST_INT_EN : 1;
00115     uint8_t DMP_INT1_EN : 1;
00116     uint8_t PLL_RDY_EN : 1;
00117     uint8_t WOM_INT_EN : 1;
00118     uint8_t REG_WOF_EN : 1;
00119     uint8_t RAW_DATA_0_RDY_EN : 1;
00120     uint8_t FIFO_OVERFLOW_EN_4 : 1;
00121     uint8_t FIFO_OVERFLOW_EN_3 : 1;
00122     uint8_t FIFO_OVERFLOW_EN_2 : 1;
00123     uint8_t FIFO_OVERFLOW_EN_1 : 1;
00124     uint8_t FIFO_OVERFLOW_EN_0 : 1;
00125     uint8_t FIFO_WM_EN_4 : 1;
00126     uint8_t FIFO_WM_EN_3 : 1;
00127     uint8_t FIFO_WM_EN_2 : 1;
00128     uint8_t FIFO_WM_EN_1 : 1;
00129     uint8_t FIFO_WM_EN_0 : 1;
00130   } ICM_20948_INT_enable_t;
00131 
00132   typedef union
00133   {
00134     ICM_20948_axis3bit16_t raw;
00135     struct
00136     {
00137       int16_t x;
00138       int16_t y;
00139       int16_t z;
00140     } axes;
00141   } ICM_20948_axis3named_t;
00142 
00143   typedef struct
00144   {
00145     ICM_20948_axis3named_t acc;
00146     ICM_20948_axis3named_t gyr;
00147     ICM_20948_axis3named_t mag;
00148     union
00149     {
00150       ICM_20948_axis1bit16_t raw;
00151       int16_t val;
00152     } tmp;
00153     ICM_20948_fss_t fss; // Full-scale range settings for this measurement
00154     uint8_t magStat1;
00155     uint8_t magStat2;
00156   } ICM_20948_AGMT_t;
00157 
00158   typedef struct
00159   {
00160     ICM_20948_Status_e (*write)(uint8_t regaddr, uint8_t *pdata, uint32_t len, void *user);
00161     ICM_20948_Status_e (*read)(uint8_t regaddr, uint8_t *pdata, uint32_t len, void *user);
00162     // void             (*delay)(uint32_t ms);
00163     void *user;
00164   } ICM_20948_Serif_t;                      // This is the vtable of serial interface functions
00165   extern const ICM_20948_Serif_t NullSerif; // Here is a default for initialization (NULL)
00166 
00167   typedef struct
00168   {
00169     const ICM_20948_Serif_t *_serif; // Pointer to the assigned Serif (Serial Interface) vtable
00170     bool _dmp_firmware_available;    // Indicates if the DMP firmware has been included. It
00171     bool _firmware_loaded;           // Indicates if DMP has been loaded
00172     uint8_t _last_bank;              // Keep track of which bank was selected last - to avoid unnecessary writes
00173     uint8_t _last_mems_bank;         // Keep track of which bank was selected last - to avoid unnecessary writes
00174     int32_t _gyroSF;                 // Use this to record the GyroSF, calculated by inv_icm20948_set_gyro_sf
00175     int8_t _gyroSFpll;
00176     uint32_t _enabled_Android_0;      // Keep track of which Android sensors are enabled: 0-31
00177     uint32_t _enabled_Android_1;      // Keep track of which Android sensors are enabled: 32-
00178     uint32_t _enabled_Android_intr_0; // Keep track of which Android sensor interrupts are enabled: 0-31
00179     uint32_t _enabled_Android_intr_1; // Keep track of which Android sensor interrupts are enabled: 32-
00180     uint16_t _dataOutCtl1;            // Diagnostics: record the setting of DATA_OUT_CTL1
00181     uint16_t _dataOutCtl2;            // Diagnostics: record the setting of DATA_OUT_CTL2
00182     uint16_t _dataRdyStatus;          // Diagnostics: record the setting of DATA_RDY_STATUS
00183     uint16_t _motionEventCtl;         // Diagnostics: record the setting of MOTION_EVENT_CTL
00184     uint16_t _dataIntrCtl;            // Diagnostics: record the setting of DATA_INTR_CTL
00185   } ICM_20948_Device_t;               // Definition of device struct type
00186 
00187   ICM_20948_Status_e ICM_20948_init_struct(ICM_20948_Device_t *pdev); // Initialize ICM_20948_Device_t
00188 
00189   // ICM_20948_Status_e ICM_20948_Startup( ICM_20948_Device_t* pdev ); // For the time being this performs a standardized startup routine
00190 
00191   ICM_20948_Status_e ICM_20948_link_serif(ICM_20948_Device_t *pdev, const ICM_20948_Serif_t *s); // Links a SERIF structure to the device
00192 
00193   // use the device's serif to perform a read or write
00194   ICM_20948_Status_e ICM_20948_execute_r(ICM_20948_Device_t *pdev, uint8_t regaddr, uint8_t *pdata, uint32_t len); // Executes a R or W witht he serif vt as long as the pointers are not null
00195   ICM_20948_Status_e ICM_20948_execute_w(ICM_20948_Device_t *pdev, uint8_t regaddr, uint8_t *pdata, uint32_t len);
00196 
00197   // Single-shot I2C on Master IF
00198   ICM_20948_Status_e ICM_20948_i2c_controller_periph4_txn(ICM_20948_Device_t *pdev, uint8_t addr, uint8_t reg, uint8_t *data, uint8_t len, bool Rw, bool send_reg_addr);
00199   ICM_20948_Status_e ICM_20948_i2c_master_single_w(ICM_20948_Device_t *pdev, uint8_t addr, uint8_t reg, uint8_t *data);
00200   ICM_20948_Status_e ICM_20948_i2c_master_single_r(ICM_20948_Device_t *pdev, uint8_t addr, uint8_t reg, uint8_t *data);
00201 
00202   // Device Level
00203   ICM_20948_Status_e ICM_20948_set_bank(ICM_20948_Device_t *pdev, uint8_t bank);                                 // Sets the bank
00204   ICM_20948_Status_e ICM_20948_sw_reset(ICM_20948_Device_t *pdev);                                               // Performs a SW reset
00205   ICM_20948_Status_e ICM_20948_sleep(ICM_20948_Device_t *pdev, bool on);                                         // Set sleep mode for the chip
00206   ICM_20948_Status_e ICM_20948_low_power(ICM_20948_Device_t *pdev, bool on);                                     // Set low power mode for the chip
00207   ICM_20948_Status_e ICM_20948_set_clock_source(ICM_20948_Device_t *pdev, ICM_20948_PWR_MGMT_1_CLKSEL_e source); // Choose clock source
00208   ICM_20948_Status_e ICM_20948_get_who_am_i(ICM_20948_Device_t *pdev, uint8_t *whoami);                          // Return whoami in out prarmeter
00209   ICM_20948_Status_e ICM_20948_check_id(ICM_20948_Device_t *pdev);                                               // Return 'ICM_20948_Stat_Ok' if whoami matches ICM_20948_WHOAMI
00210   ICM_20948_Status_e ICM_20948_data_ready(ICM_20948_Device_t *pdev);                                             // Returns 'Ok' if data is ready
00211 
00212   // Interrupt Configuration
00213   ICM_20948_Status_e ICM_20948_int_pin_cfg(ICM_20948_Device_t *pdev, ICM_20948_INT_PIN_CFG_t *write, ICM_20948_INT_PIN_CFG_t *read); // Set the INT pin configuration
00214   ICM_20948_Status_e ICM_20948_int_enable(ICM_20948_Device_t *pdev, ICM_20948_INT_enable_t *write, ICM_20948_INT_enable_t *read);    // Write and or read the interrupt enable information. If non-null the write operation occurs before the read, so as to verify that the write was successful
00215 
00216   // WoM Threshold Level Configuration
00217   ICM_20948_Status_e ICM_20948_wom_threshold(ICM_20948_Device_t *pdev, ICM_20948_ACCEL_WOM_THR_t *write, ICM_20948_ACCEL_WOM_THR_t *read); // Write and or read the Wake on Motion threshold. If non-null the write operation occurs before the read, so as to verify that the write was successful
00218 
00219   // Internal Sensor Options
00220   ICM_20948_Status_e ICM_20948_set_sample_mode(ICM_20948_Device_t *pdev, ICM_20948_InternalSensorID_bm sensors, ICM_20948_LP_CONFIG_CYCLE_e mode); // Use to set accel, gyro, and I2C master into cycled or continuous modes
00221   ICM_20948_Status_e ICM_20948_set_full_scale(ICM_20948_Device_t *pdev, ICM_20948_InternalSensorID_bm sensors, ICM_20948_fss_t fss);
00222   ICM_20948_Status_e ICM_20948_set_dlpf_cfg(ICM_20948_Device_t *pdev, ICM_20948_InternalSensorID_bm sensors, ICM_20948_dlpcfg_t cfg);
00223   ICM_20948_Status_e ICM_20948_enable_dlpf(ICM_20948_Device_t *pdev, ICM_20948_InternalSensorID_bm sensors, bool enable);
00224   ICM_20948_Status_e ICM_20948_set_sample_rate(ICM_20948_Device_t *pdev, ICM_20948_InternalSensorID_bm sensors, ICM_20948_smplrt_t smplrt);
00225 
00226   // Interface Things
00227   ICM_20948_Status_e ICM_20948_i2c_master_passthrough(ICM_20948_Device_t *pdev, bool passthrough);
00228   ICM_20948_Status_e ICM_20948_i2c_master_enable(ICM_20948_Device_t *pdev, bool enable);
00229   ICM_20948_Status_e ICM_20948_i2c_master_reset(ICM_20948_Device_t *pdev);
00230   ICM_20948_Status_e ICM_20948_i2c_controller_configure_peripheral(ICM_20948_Device_t *pdev, uint8_t peripheral, uint8_t addr, uint8_t reg, uint8_t len, bool Rw, bool enable, bool data_only, bool grp, bool swap, uint8_t dataOut);
00231 
00232   // Higher Level
00233   ICM_20948_Status_e ICM_20948_get_agmt(ICM_20948_Device_t *pdev, ICM_20948_AGMT_t *p);
00234 
00235   // FIFO
00236 
00237   ICM_20948_Status_e ICM_20948_enable_FIFO(ICM_20948_Device_t *pdev, bool enable);
00238   ICM_20948_Status_e ICM_20948_reset_FIFO(ICM_20948_Device_t *pdev);
00239   ICM_20948_Status_e ICM_20948_set_FIFO_mode(ICM_20948_Device_t *pdev, bool snapshot);
00240   ICM_20948_Status_e ICM_20948_get_FIFO_count(ICM_20948_Device_t *pdev, uint16_t *count);
00241   ICM_20948_Status_e ICM_20948_read_FIFO(ICM_20948_Device_t *pdev, uint8_t *data, uint8_t len);
00242 
00243   // DMP
00244 
00245   ICM_20948_Status_e ICM_20948_enable_DMP(ICM_20948_Device_t *pdev, bool enable);
00246   ICM_20948_Status_e ICM_20948_reset_DMP(ICM_20948_Device_t *pdev);
00247   ICM_20948_Status_e ICM_20948_firmware_load(ICM_20948_Device_t *pdev);
00248   ICM_20948_Status_e ICM_20948_set_dmp_start_address(ICM_20948_Device_t *pdev, unsigned short address);
00249 
00250   /** @brief Loads the DMP firmware from SRAM
00251     * @param[in] data  pointer where the image
00252     * @param[in] size  size if the image
00253     * @param[in] load_addr  address to loading the image
00254     * @return 0 in case of success, -1 for any error
00255     */
00256   ICM_20948_Status_e inv_icm20948_firmware_load(ICM_20948_Device_t *pdev, const unsigned char *data, unsigned short size, unsigned short load_addr);
00257   /**
00258     *  @brief       Write data to a register in DMP memory
00259     *  @param[in]   DMP memory address
00260     *  @param[in]   number of byte to be written
00261     *  @param[out]  output data from the register
00262     *  @return     0 if successful.
00263     */
00264   ICM_20948_Status_e inv_icm20948_write_mems(ICM_20948_Device_t *pdev, unsigned short reg, unsigned int length, const unsigned char *data);
00265   /**
00266     *  @brief      Read data from a register in DMP memory
00267     *  @param[in]  DMP memory address
00268     *  @param[in]  number of byte to be read
00269     *  @param[in]  input data from the register
00270     *  @return     0 if successful.
00271     */
00272   ICM_20948_Status_e inv_icm20948_read_mems(ICM_20948_Device_t *pdev, unsigned short reg, unsigned int length, unsigned char *data);
00273 
00274   ICM_20948_Status_e inv_icm20948_set_dmp_sensor_period(ICM_20948_Device_t *pdev, enum DMP_ODR_Registers odr_reg, uint16_t interval);
00275   ICM_20948_Status_e inv_icm20948_enable_dmp_sensor(ICM_20948_Device_t *pdev, enum inv_icm20948_sensor sensor, int state);     // State is actually boolean
00276   ICM_20948_Status_e inv_icm20948_enable_dmp_sensor_int(ICM_20948_Device_t *pdev, enum inv_icm20948_sensor sensor, int state); // State is actually boolean
00277   uint8_t sensor_type_2_android_sensor(enum inv_icm20948_sensor sensor);
00278   enum inv_icm20948_sensor inv_icm20948_sensor_android_2_sensor_type(int sensor);
00279 
00280   ICM_20948_Status_e inv_icm20948_read_dmp_data(ICM_20948_Device_t *pdev, icm_20948_DMP_data_t *data);
00281   ICM_20948_Status_e inv_icm20948_set_gyro_sf(ICM_20948_Device_t *pdev, unsigned char div, int gyro_level);
00282 
00283   // ToDo:
00284 
00285   /*
00286     Want to access magnetometer throught the I2C master interface...
00287 
00288   // If using the I2C master to read from the magnetometer
00289   // Enable the I2C master to talk to the magnetometer through the ICM 20948
00290   myICM.i2cMasterEnable( true );
00291   SERIAL_PORT.print(F("Enabling the I2C master returned ")); SERIAL_PORT.println(myICM.statusString());
00292   myICM.i2cControllerConfigurePeripheral ( 0, MAG_AK09916_I2C_ADDR, REG_ST1, 9, true, true, false, false, false );
00293   SERIAL_PORT.print(F("Configuring the magnetometer peripheral returned ")); SERIAL_PORT.println(myICM.statusString());
00294 
00295   // Operate the I2C master in duty-cycled mode
00296   myICM.setSampleMode( (ICM_20948_Internal_Mst | ICM_20948_Internal_Gyr), ICM_20948_Sample_Mode_Cycled ); // options: ICM_20948_Sample_Mode_Continuous or ICM_20948_Sample_Mode_Cycled
00297 */
00298 
00299 #ifdef __cplusplus
00300 }
00301 #endif /* __cplusplus */
00302 
00303 #endif /* _ICM_20948_C_H_ */