XerolySkinnerBscpp 1.0.0
C++版本的驱动库
inv_mpu.c
浏览该文件的文档.
1/*
2 $License:
3 Copyright (C) 2011-2012 InvenSense Corporation, All Rights Reserved.
4 See included License.txt for License information.
5 $
6 */
20#include <stdio.h>
21#include <stdlib.h>
22#include <string.h>
23#include <math.h>
24#include "inv_mpu.h"
26#include "mpu6050.h"
27#include "usart.h"
28#include "varint.h"
29
30#define MPU6050 //定义我们使用的传感器为MPU6050
31#define MOTION_DRIVER_TARGET_MSP430 //定义驱动部分,采用MSP430的驱动(移植到STM32F1)
32
33/* The following functions must be defined for this platform:
34 * i2c_write(unsigned char slave_addr, unsigned char reg_addr,
35 * unsigned char length, unsigned char const *data)
36 * i2c_read(unsigned char slave_addr, unsigned char reg_addr,
37 * unsigned char length, unsigned char *data)
38 * delay_ms(unsigned long num_ms)
39 * get_ms(unsigned long *count)
40 * reg_int_cb(void (*cb)(void), unsigned char port, unsigned char pin)
41 * labs(long x)
42 * fabsf(float x)
43 * min(int a, int b)
44 */
45#if defined MOTION_DRIVER_TARGET_MSP430
46
47#define i2c_write MPU_Write_Len
48#define i2c_read MPU_Read_Len
49#define delay_ms HAL_Delay
50#define get_ms mget_ms
51//static inline int reg_int_cb(struct int_param_s *int_param)
52//{
53// return msp430_reg_int_cb(int_param->cb, int_param->pin, int_param->lp_exit,
54// int_param->active_low);
55//}
56void log_none(char *fmt,...){;}
57#define log_i log_none //打印信息
58#define log_e log_none //打印信息
59/* labs is already defined by TI's toolchain. */
60/* fabs is for doubles. fabsf is for floats. */
61#define fabs fabsf
62#define min(a,b) ((a<b)?a:b)
63#elif defined EMPL_TARGET_MSP430
64#include "msp430.h"
65#include "msp430_i2c.h"
66#include "msp430_clock.h"
67#include "msp430_interrupt.h"
68#include "log.h"
69#define i2c_write msp430_i2c_write
70#define i2c_read msp430_i2c_read
71#define delay_ms msp430_delay_ms
72#define get_ms msp430_get_clock_ms
73static inline int reg_int_cb(struct int_param_s *int_param)
74{
75 return msp430_reg_int_cb(int_param->cb, int_param->pin, int_param->lp_exit,
76 int_param->active_low);
77}
78#define log_i MPL_LOGI
79#define log_e MPL_LOGE
80/* labs is already defined by TI's toolchain. */
81/* fabs is for doubles. fabsf is for floats. */
82#define fabs fabsf
83#define min(a,b) ((a<b)?a:b)
84#elif defined EMPL_TARGET_UC3L0
85/* Instead of using the standard TWI driver from the ASF library, we're using
86 * a TWI driver that follows the slave address + register address convention.
87 */
88#include "twi.h"
89#include "delay.h"
90#include "sysclk.h"
91#include "log.h"
92#include "sensors_xplained.h"
93#include "uc3l0_clock.h"
94#define i2c_write(a, b, c, d) twi_write(a, b, d, c)
95#define i2c_read(a, b, c, d) twi_read(a, b, d, c)
96/* delay_ms is a function already defined in ASF. */
97#define get_ms uc3l0_get_clock_ms
98static inline int reg_int_cb(struct int_param_s *int_param)
99{
100 sensor_board_irq_connect(int_param->pin, int_param->cb, int_param->arg);
101 return 0;
102}
103#define log_i MPL_LOGI
104#define log_e MPL_LOGE
105/* UC3 is a 32-bit processor, so abs and labs are equivalent. */
106#define labs abs
107#define fabs(x) (((x)>0)?(x):-(x))
108#else
109#error Gyro driver is missing the system layer implementations.
110#endif
111
112#if !defined MPU6050 && !defined MPU9150 && !defined MPU6500 && !defined MPU9250
113#error Which gyro are you using? Define MPUxxxx in your compiler options.
114#endif
115
116/* Time for some messy macro work. =]
117 * #define MPU9150
118 * is equivalent to..
119 * #define MPU6050
120 * #define AK8975_SECONDARY
121 *
122 * #define MPU9250
123 * is equivalent to..
124 * #define MPU6500
125 * #define AK8963_SECONDARY
126 */
127#if defined MPU9150
128#ifndef MPU6050
129#define MPU6050
130#endif /* #ifndef MPU6050 */
131#if defined AK8963_SECONDARY
132#error "MPU9150 and AK8963_SECONDARY cannot both be defined."
133#elif !defined AK8975_SECONDARY /* #if defined AK8963_SECONDARY */
134#define AK8975_SECONDARY
135#endif /* #if defined AK8963_SECONDARY */
136#elif defined MPU9250 /* #if defined MPU9150 */
137#ifndef MPU6500
138#define MPU6500
139#endif /* #ifndef MPU6500 */
140#if defined AK8975_SECONDARY
141#error "MPU9250 and AK8975_SECONDARY cannot both be defined."
142#elif !defined AK8963_SECONDARY /* #if defined AK8975_SECONDARY */
143#define AK8963_SECONDARY
144#endif /* #if defined AK8975_SECONDARY */
145#endif /* #if defined MPU9150 */
146
147#if defined AK8975_SECONDARY || defined AK8963_SECONDARY
148#define AK89xx_SECONDARY
149#else
150/* #warning "No compass = less profit for Invensense. Lame." */
151#endif
152
153static int set_int_enable(unsigned char enable);
154
155/* Hardware registers needed by driver. */
157 unsigned char who_am_i;
158 unsigned char rate_div;
159 unsigned char lpf;
160 unsigned char prod_id;
161 unsigned char user_ctrl;
162 unsigned char fifo_en;
163 unsigned char gyro_cfg;
164 unsigned char accel_cfg;
165// unsigned char accel_cfg2;
166// unsigned char lp_accel_odr;
167 unsigned char motion_thr;
168 unsigned char motion_dur;
169 unsigned char fifo_count_h;
170 unsigned char fifo_r_w;
171 unsigned char raw_gyro;
172 unsigned char raw_accel;
173 unsigned char temp;
174 unsigned char int_enable;
175 unsigned char dmp_int_status;
176 unsigned char int_status;
177// unsigned char accel_intel;
178 unsigned char pwr_mgmt_1;
179 unsigned char pwr_mgmt_2;
180 unsigned char int_pin_cfg;
181 unsigned char mem_r_w;
182 unsigned char accel_offs;
183 unsigned char i2c_mst;
184 unsigned char bank_sel;
185 unsigned char mem_start_addr;
186 unsigned char prgm_start_h;
187#if defined AK89xx_SECONDARY
188 unsigned char s0_addr;
189 unsigned char s0_reg;
190 unsigned char s0_ctrl;
191 unsigned char s1_addr;
192 unsigned char s1_reg;
193 unsigned char s1_ctrl;
194 unsigned char s4_ctrl;
195 unsigned char s0_do;
196 unsigned char s1_do;
197 unsigned char i2c_delay_ctrl;
198 unsigned char raw_compass;
199 /* The I2C_MST_VDDIO bit is in this register. */
200 unsigned char yg_offs_tc;
201#endif
202};
203
204/* Information specific to a particular device. */
205struct hw_s {
206 unsigned char addr;
207 unsigned short max_fifo;
208 unsigned char num_reg;
209 unsigned short temp_sens;
211 unsigned short bank_size;
212#if defined AK89xx_SECONDARY
213 unsigned short compass_fsr;
214#endif
215};
216
217/* When entering motion interrupt mode, the driver keeps track of the
218 * previous state so that it can be restored at a later time.
219 * TODO: This is tacky. Fix it.
220 */
222 unsigned short gyro_fsr;
223 unsigned char accel_fsr;
224 unsigned short lpf;
225 unsigned short sample_rate;
226 unsigned char sensors_on;
227 unsigned char fifo_sensors;
228 unsigned char dmp_on;
229};
230
231/* Cached chip configuration data.
232 * TODO: A lot of these can be handled with a bitmask.
233 */
235 /* Matches gyro_cfg >> 3 & 0x03 */
236 unsigned char gyro_fsr;
237 /* Matches accel_cfg >> 3 & 0x03 */
238 unsigned char accel_fsr;
239 /* Enabled sensors. Uses same masks as fifo_en, NOT pwr_mgmt_2. */
240 unsigned char sensors;
241 /* Matches config register. */
242 unsigned char lpf;
243 unsigned char clk_src;
244 /* Sample rate, NOT rate divider. */
245 unsigned short sample_rate;
246 /* Matches fifo_en register. */
247 unsigned char fifo_enable;
248 /* Matches int enable register. */
249 unsigned char int_enable;
250 /* 1 if devices on auxiliary I2C bus appear on the primary. */
251 unsigned char bypass_mode;
252 /* 1 if half-sensitivity.
253 * NOTE: This doesn't belong here, but everything else in hw_s is const,
254 * and this allows us to save some precious RAM.
255 */
256 unsigned char accel_half;
257 /* 1 if device in low-power accel-only mode. */
258 unsigned char lp_accel_mode;
259 /* 1 if interrupts are only triggered on motion events. */
260 unsigned char int_motion_only;
262 /* 1 for active low interrupts. */
263 unsigned char active_low_int;
264 /* 1 for latched interrupts. */
265 unsigned char latched_int;
266 /* 1 if DMP is enabled. */
267 unsigned char dmp_on;
268 /* Ensures that DMP will only be loaded once. */
269 unsigned char dmp_loaded;
270 /* Sampling rate used when DMP is enabled. */
271 unsigned short dmp_sample_rate;
272#ifdef AK89xx_SECONDARY
273 /* Compass sample rate. */
274 unsigned short compass_sample_rate;
275 unsigned char compass_addr;
276 short mag_sens_adj[3];
277#endif
278};
279
280/* Information for self-test. */
281struct test_s {
282 unsigned long gyro_sens;
283 unsigned long accel_sens;
284 unsigned char reg_rate_div;
285 unsigned char reg_lpf;
286 unsigned char reg_gyro_fsr;
287 unsigned char reg_accel_fsr;
288 unsigned short wait_ms;
289 unsigned char packet_thresh;
290 float min_dps;
291 float max_dps;
293 float min_g;
294 float max_g;
296};
297
298/* Gyro driver state variables. */
300 const struct gyro_reg_s *reg;
301 const struct hw_s *hw;
303 const struct test_s *test;
304};
305
306/* Filter configurations. */
307enum lpf_e {
318
319/* Full scale ranges. */
327
328/* Full scale ranges. */
336
337/* Clock sources. */
341 NUM_CLK
343
344/* Low-power accel wakeup rates. */
346#if defined MPU6050
351#elif defined MPU6500
352 INV_LPA_0_3125HZ,
353 INV_LPA_0_625HZ,
355 INV_LPA_2_5HZ,
357 INV_LPA_10HZ,
360 INV_LPA_80HZ,
361 INV_LPA_160HZ,
362 INV_LPA_320HZ,
363 INV_LPA_640HZ
364#endif
366
367#define BIT_I2C_MST_VDDIO (0x80)
368#define BIT_FIFO_EN (0x40)
369#define BIT_DMP_EN (0x80)
370#define BIT_FIFO_RST (0x04)
371#define BIT_DMP_RST (0x08)
372#define BIT_FIFO_OVERFLOW (0x10)
373#define BIT_DATA_RDY_EN (0x01)
374#define BIT_DMP_INT_EN (0x02)
375#define BIT_MOT_INT_EN (0x40)
376#define BITS_FSR (0x18)
377#define BITS_LPF (0x07)
378#define BITS_HPF (0x07)
379#define BITS_CLK (0x07)
380#define BIT_FIFO_SIZE_1024 (0x40)
381#define BIT_FIFO_SIZE_2048 (0x80)
382#define BIT_FIFO_SIZE_4096 (0xC0)
383#define BIT_RESET (0x80)
384#define BIT_SLEEP (0x40)
385#define BIT_S0_DELAY_EN (0x01)
386#define BIT_S2_DELAY_EN (0x04)
387#define BITS_SLAVE_LENGTH (0x0F)
388#define BIT_SLAVE_BYTE_SW (0x40)
389#define BIT_SLAVE_GROUP (0x10)
390#define BIT_SLAVE_EN (0x80)
391#define BIT_I2C_READ (0x80)
392#define BITS_I2C_MASTER_DLY (0x1F)
393#define BIT_AUX_IF_EN (0x20)
394#define BIT_ACTL (0x80)
395#define BIT_LATCH_EN (0x20)
396#define BIT_ANY_RD_CLR (0x10)
397#define BIT_BYPASS_EN (0x02)
398#define BITS_WOM_EN (0xC0)
399#define BIT_LPA_CYCLE (0x20)
400#define BIT_STBY_XA (0x20)
401#define BIT_STBY_YA (0x10)
402#define BIT_STBY_ZA (0x08)
403#define BIT_STBY_XG (0x04)
404#define BIT_STBY_YG (0x02)
405#define BIT_STBY_ZG (0x01)
406#define BIT_STBY_XYZA (BIT_STBY_XA | BIT_STBY_YA | BIT_STBY_ZA)
407#define BIT_STBY_XYZG (BIT_STBY_XG | BIT_STBY_YG | BIT_STBY_ZG)
408
409#if defined AK8975_SECONDARY
410#define SUPPORTS_AK89xx_HIGH_SENS (0x00)
411#define AK89xx_FSR (9830)
412#elif defined AK8963_SECONDARY
413#define SUPPORTS_AK89xx_HIGH_SENS (0x10)
414#define AK89xx_FSR (4915)
415#endif
416
417#ifdef AK89xx_SECONDARY
418#define AKM_REG_WHOAMI (0x00)
419
420#define AKM_REG_ST1 (0x02)
421#define AKM_REG_HXL (0x03)
422#define AKM_REG_ST2 (0x09)
423
424#define AKM_REG_CNTL (0x0A)
425#define AKM_REG_ASTC (0x0C)
426#define AKM_REG_ASAX (0x10)
427#define AKM_REG_ASAY (0x11)
428#define AKM_REG_ASAZ (0x12)
429
430#define AKM_DATA_READY (0x01)
431#define AKM_DATA_OVERRUN (0x02)
432#define AKM_OVERFLOW (0x80)
433#define AKM_DATA_ERROR (0x40)
434
435#define AKM_BIT_SELF_TEST (0x40)
436
437#define AKM_POWER_DOWN (0x00 | SUPPORTS_AK89xx_HIGH_SENS)
438#define AKM_SINGLE_MEASUREMENT (0x01 | SUPPORTS_AK89xx_HIGH_SENS)
439#define AKM_FUSE_ROM_ACCESS (0x0F | SUPPORTS_AK89xx_HIGH_SENS)
440#define AKM_MODE_SELF_TEST (0x08 | SUPPORTS_AK89xx_HIGH_SENS)
441
442#define AKM_WHOAMI (0x48)
443#endif
444
445#if defined MPU6050
446//const struct gyro_reg_s reg = {
447// .who_am_i = 0x75,
448// .rate_div = 0x19,
449// .lpf = 0x1A,
450// .prod_id = 0x0C,
451// .user_ctrl = 0x6A,
452// .fifo_en = 0x23,
453// .gyro_cfg = 0x1B,
454// .accel_cfg = 0x1C,
455// .motion_thr = 0x1F,
456// .motion_dur = 0x20,
457// .fifo_count_h = 0x72,
458// .fifo_r_w = 0x74,
459// .raw_gyro = 0x43,
460// .raw_accel = 0x3B,
461// .temp = 0x41,
462// .int_enable = 0x38,
463// .dmp_int_status = 0x39,
464// .int_status = 0x3A,
465// .pwr_mgmt_1 = 0x6B,
466// .pwr_mgmt_2 = 0x6C,
467// .int_pin_cfg = 0x37,
468// .mem_r_w = 0x6F,
469// .accel_offs = 0x06,
470// .i2c_mst = 0x24,
471// .bank_sel = 0x6D,
472// .mem_start_addr = 0x6E,
473// .prgm_start_h = 0x70
474//#ifdef AK89xx_SECONDARY
475// ,.raw_compass = 0x49,
476// .yg_offs_tc = 0x01,
477// .s0_addr = 0x25,
478// .s0_reg = 0x26,
479// .s0_ctrl = 0x27,
480// .s1_addr = 0x28,
481// .s1_reg = 0x29,
482// .s1_ctrl = 0x2A,
483// .s4_ctrl = 0x34,
484// .s0_do = 0x63,
485// .s1_do = 0x64,
486// .i2c_delay_ctrl = 0x67
487//#endif
488//};
489const struct gyro_reg_s reg = {
4900x75, //who_am_i
4910x19, //rate_div
4920x1A, //lpf
4930x0C, //prod_id
4940x6A, //user_ctrl
4950x23, //fifo_en
4960x1B, //gyro_cfg
4970x1C, //accel_cfg
4980x1F, // motion_thr
4990x20, // motion_dur
5000x72, // fifo_count_h
5010x74, // fifo_r_w
5020x43, // raw_gyro
5030x3B, // raw_accel
5040x41, // temp
5050x38, // int_enable
5060x39, // dmp_int_status
5070x3A, // int_status
5080x6B, // pwr_mgmt_1
5090x6C, // pwr_mgmt_2
5100x37, // int_pin_cfg
5110x6F, // mem_r_w
5120x06, // accel_offs
5130x24, // i2c_mst
5140x6D, // bank_sel
5150x6E, // mem_start_addr
5160x70 // prgm_start_h
517};
518
519//const struct hw_s hw = {
520// .addr = 0x68,
521// .max_fifo = 1024,
522// .num_reg = 118,
523// .temp_sens = 340,
524// .temp_offset = -521,
525// .bank_size = 256
526//#if defined AK89xx_SECONDARY
527// ,.compass_fsr = AK89xx_FSR
528//#endif
529//};
530const struct hw_s hw={
531 0x68, //addr
532 1024, //max_fifo
533 118, //num_reg
534 340, //temp_sens
535 -521, //temp_offset
536 256 //bank_size
537};
538
539//const struct test_s test = {
540// .gyro_sens = 32768/250,
541// .accel_sens = 32768/16,
542// .reg_rate_div = 0, /* 1kHz. */
543// .reg_lpf = 1, /* 188Hz. */
544// .reg_gyro_fsr = 0, /* 250dps. */
545// .reg_accel_fsr = 0x18, /* 16g. */
546// .wait_ms = 50,
547// .packet_thresh = 5, /* 5% */
548// .min_dps = 10.f,
549// .max_dps = 105.f,
550// .max_gyro_var = 0.14f,
551// .min_g = 0.3f,
552// .max_g = 0.95f,
553// .max_accel_var = 0.14f
554//};
555const struct test_s test={
55632768/250, //gyro_sens
55732768/16, // accel_sens
5580, // reg_rate_div
5591, // reg_lpf
5600, // reg_gyro_fsr
5610x18, // reg_accel_fsr
56250, // wait_ms
5635, // packet_thresh
56410.0f, // min_dps
565105.0f, // max_dps
5660.14f, // max_gyro_var
5670.3f, // min_g
5680.95f, // max_g
5690.14f // max_accel_var
570};
571
572//static struct gyro_state_s st = {
573// .reg = &reg,
574// .hw = &hw,
575// .test = &test
576//};
577static struct gyro_state_s st={
578 &reg,
579 &hw,
580 {0},
581 &test
582};
583
584
585#elif defined MPU6500
586const struct gyro_reg_s reg = {
587 .who_am_i = 0x75,
588 .rate_div = 0x19,
589 .lpf = 0x1A,
590 .prod_id = 0x0C,
591 .user_ctrl = 0x6A,
592 .fifo_en = 0x23,
593 .gyro_cfg = 0x1B,
594 .accel_cfg = 0x1C,
595 .accel_cfg2 = 0x1D,
596 .lp_accel_odr = 0x1E,
597 .motion_thr = 0x1F,
598 .motion_dur = 0x20,
599 .fifo_count_h = 0x72,
600 .fifo_r_w = 0x74,
601 .raw_gyro = 0x43,
602 .raw_accel = 0x3B,
603 .temp = 0x41,
604 .int_enable = 0x38,
605 .dmp_int_status = 0x39,
606 .int_status = 0x3A,
607 .accel_intel = 0x69,
608 .pwr_mgmt_1 = 0x6B,
609 .pwr_mgmt_2 = 0x6C,
610 .int_pin_cfg = 0x37,
611 .mem_r_w = 0x6F,
612 .accel_offs = 0x77,
613 .i2c_mst = 0x24,
614 .bank_sel = 0x6D,
615 .mem_start_addr = 0x6E,
616 .prgm_start_h = 0x70
617#ifdef AK89xx_SECONDARY
618 ,.raw_compass = 0x49,
619 .s0_addr = 0x25,
620 .s0_reg = 0x26,
621 .s0_ctrl = 0x27,
622 .s1_addr = 0x28,
623 .s1_reg = 0x29,
624 .s1_ctrl = 0x2A,
625 .s4_ctrl = 0x34,
626 .s0_do = 0x63,
627 .s1_do = 0x64,
628 .i2c_delay_ctrl = 0x67
629#endif
630};
631const struct hw_s hw = {
632 .addr = 0x68,
633 .max_fifo = 1024,
634 .num_reg = 128,
635 .temp_sens = 321,
636 .temp_offset = 0,
637 .bank_size = 256
638#if defined AK89xx_SECONDARY
639 ,.compass_fsr = AK89xx_FSR
640#endif
641};
642
643const struct test_s test = {
644 .gyro_sens = 32768/250,
645 .accel_sens = 32768/16,
646 .reg_rate_div = 0, /* 1kHz. */
647 .reg_lpf = 1, /* 188Hz. */
648 .reg_gyro_fsr = 0, /* 250dps. */
649 .reg_accel_fsr = 0x18, /* 16g. */
650 .wait_ms = 50,
651 .packet_thresh = 5, /* 5% */
652 .min_dps = 10.f,
653 .max_dps = 105.f,
654 .max_gyro_var = 0.14f,
655 .min_g = 0.3f,
656 .max_g = 0.95f,
657 .max_accel_var = 0.14f
658};
659
660static struct gyro_state_s st = {
661 .reg = &reg,
662 .hw = &hw,
663 .test = &test
664};
665#endif
666
667#define MAX_PACKET_LENGTH (12)
668
669#ifdef AK89xx_SECONDARY
670static int setup_compass(void);
671#define MAX_COMPASS_SAMPLE_RATE (100)
672#endif
673
681static int set_int_enable(unsigned char enable)
682{
683 unsigned char tmp;
684
685 if (st.chip_cfg.dmp_on) {
686 if (enable)
687 tmp = BIT_DMP_INT_EN;
688 else
689 tmp = 0x00;
690 if (i2c_write(st.hw->addr, st.reg->int_enable, 1, &tmp))
691 return -1;
692 st.chip_cfg.int_enable = tmp;
693 } else {
694 if (!st.chip_cfg.sensors)
695 return -1;
696 if (enable && st.chip_cfg.int_enable)
697 return 0;
698 if (enable)
699 tmp = BIT_DATA_RDY_EN;
700 else
701 tmp = 0x00;
702 if (i2c_write(st.hw->addr, st.reg->int_enable, 1, &tmp))
703 return -1;
704 st.chip_cfg.int_enable = tmp;
705 }
706 return 0;
707}
708
714{
715 unsigned char ii;
716 unsigned char data;
717
718 for (ii = 0; ii < st.hw->num_reg; ii++) {
719 if (ii == st.reg->fifo_r_w || ii == st.reg->mem_r_w)
720 continue;
721 if (i2c_read(st.hw->addr, ii, 1, &data))
722 return -1;
723 log_i("%#5x: %#5x\r\n", ii, data);
724 }
725 return 0;
726}
727
735int mpu_read_reg(unsigned char reg, unsigned char *data)
736{
737 if (reg == st.reg->fifo_r_w || reg == st.reg->mem_r_w)
738 return -1;
739 if (reg >= st.hw->num_reg)
740 return -1;
741 return i2c_read(st.hw->addr, reg, 1, data);
742}
743
757int mpu_init(void)
758{
759 unsigned char data[6], rev;
760
761 /* Reset device. */
762 data[0] = BIT_RESET;
763 if (i2c_write(st.hw->addr, st.reg->pwr_mgmt_1, 1, data))
764 return -1;
765 delay_ms(100);
766
767 /* Wake up chip. */
768 data[0] = 0x00;
769 if (i2c_write(st.hw->addr, st.reg->pwr_mgmt_1, 1, data))
770 return -1;
771
772#if defined MPU6050
773 /* Check product revision. */
774 if (i2c_read(st.hw->addr, st.reg->accel_offs, 6, data))
775 return -1;
776 rev = ((data[5] & 0x01) << 2) | ((data[3] & 0x01) << 1) |
777 (data[1] & 0x01);
778
779 if (rev) {
780 /* Congrats, these parts are better. */
781 if (rev == 1)
783 else if (rev == 2)
785 else {
786 log_e("Unsupported software product rev %d.\n", rev);
787 return -1;
788 }
789 } else {
790 if (i2c_read(st.hw->addr, st.reg->prod_id, 1, data))
791 return -1;
792 rev = data[0] & 0x0F;
793 if (!rev) {
794 log_e("Product ID read as 0 indicates device is either "
795 "incompatible or an MPU3050.\n");
796 return -1;
797 } else if (rev == 4) {
798 log_i("Half sensitivity part found.\n");
800 } else
802 }
803#elif defined MPU6500
804#define MPU6500_MEM_REV_ADDR (0x17)
805 if (mpu_read_mem(MPU6500_MEM_REV_ADDR, 1, &rev))
806 return -1;
807 if (rev == 0x1)
809 else {
810 log_e("Unsupported software product rev %d.\n", rev);
811 return -1;
812 }
813
814 /* MPU6500 shares 4kB of memory between the DMP and the FIFO. Since the
815 * first 3kB are needed by the DMP, we'll use the last 1kB for the FIFO.
816 */
817 data[0] = BIT_FIFO_SIZE_1024 | 0x8;
818 if (i2c_write(st.hw->addr, st.reg->accel_cfg2, 1, data))
819 return -1;
820#endif
821
822 /* Set to invalid values to ensure no I2C writes are skipped. */
823 st.chip_cfg.sensors = 0xFF;
824 st.chip_cfg.gyro_fsr = 0xFF;
825 st.chip_cfg.accel_fsr = 0xFF;
826 st.chip_cfg.lpf = 0xFF;
827 st.chip_cfg.sample_rate = 0xFFFF;
828 st.chip_cfg.fifo_enable = 0xFF;
829 st.chip_cfg.bypass_mode = 0xFF;
830#ifdef AK89xx_SECONDARY
831 st.chip_cfg.compass_sample_rate = 0xFFFF;
832#endif
833 /* mpu_set_sensors always preserves this setting. */
835 /* Handled in next call to mpu_set_bypass. */
840 memset(&st.chip_cfg.cache, 0, sizeof(st.chip_cfg.cache));
841 st.chip_cfg.dmp_on = 0;
844
845 if (mpu_set_gyro_fsr(2000))
846 return -1;
847 if (mpu_set_accel_fsr(2))
848 return -1;
849 if (mpu_set_lpf(42))
850 return -1;
851 if (mpu_set_sample_rate(50))
852 return -1;
853 if (mpu_configure_fifo(0))
854 return -1;
855
856// if (int_param)
857// reg_int_cb(int_param);
858
859#ifdef AK89xx_SECONDARY
862 return -1;
863#else
864 /* Already disabled by setup_compass. */
865 if (mpu_set_bypass(0))
866 return -1;
867#endif
868
870 return 0;
871}
872
888int mpu_lp_accel_mode(unsigned char rate)
889{
890 unsigned char tmp[2];
891
892 if (rate > 40)
893 return -1;
894
895 if (!rate) {
897 tmp[0] = 0;
898 tmp[1] = BIT_STBY_XYZG;
899 if (i2c_write(st.hw->addr, st.reg->pwr_mgmt_1, 2, tmp))
900 return -1;
902 return 0;
903 }
904 /* For LP accel, we automatically configure the hardware to produce latched
905 * interrupts. In LP accel mode, the hardware cycles into sleep mode before
906 * it gets a chance to deassert the interrupt pin; therefore, we shift this
907 * responsibility over to the MCU.
908 *
909 * Any register read will clear the interrupt.
910 */
912#if defined MPU6050
913 tmp[0] = BIT_LPA_CYCLE;
914 if (rate == 1) {
915 tmp[1] = INV_LPA_1_25HZ;
916 mpu_set_lpf(5);
917 } else if (rate <= 5) {
918 tmp[1] = INV_LPA_5HZ;
919 mpu_set_lpf(5);
920 } else if (rate <= 20) {
921 tmp[1] = INV_LPA_20HZ;
922 mpu_set_lpf(10);
923 } else {
924 tmp[1] = INV_LPA_40HZ;
925 mpu_set_lpf(20);
926 }
927 tmp[1] = (tmp[1] << 6) | BIT_STBY_XYZG;
928 if (i2c_write(st.hw->addr, st.reg->pwr_mgmt_1, 2, tmp))
929 return -1;
930#elif defined MPU6500
931 /* Set wake frequency. */
932 if (rate == 1)
933 tmp[0] = INV_LPA_1_25HZ;
934 else if (rate == 2)
935 tmp[0] = INV_LPA_2_5HZ;
936 else if (rate <= 5)
937 tmp[0] = INV_LPA_5HZ;
938 else if (rate <= 10)
939 tmp[0] = INV_LPA_10HZ;
940 else if (rate <= 20)
941 tmp[0] = INV_LPA_20HZ;
942 else if (rate <= 40)
943 tmp[0] = INV_LPA_40HZ;
944 else if (rate <= 80)
945 tmp[0] = INV_LPA_80HZ;
946 else if (rate <= 160)
947 tmp[0] = INV_LPA_160HZ;
948 else if (rate <= 320)
949 tmp[0] = INV_LPA_320HZ;
950 else
951 tmp[0] = INV_LPA_640HZ;
952 if (i2c_write(st.hw->addr, st.reg->lp_accel_odr, 1, tmp))
953 return -1;
954 tmp[0] = BIT_LPA_CYCLE;
955 if (i2c_write(st.hw->addr, st.reg->pwr_mgmt_1, 1, tmp))
956 return -1;
957#endif
959 st.chip_cfg.clk_src = 0;
962
963 return 0;
964}
965
972int mpu_get_gyro_reg(short *data, unsigned long *timestamp)
973{
974 unsigned char tmp[6];
975
977 return -1;
978
979 if (i2c_read(st.hw->addr, st.reg->raw_gyro, 6, tmp))
980 return -1;
981 data[0] = (tmp[0] << 8) | tmp[1];
982 data[1] = (tmp[2] << 8) | tmp[3];
983 data[2] = (tmp[4] << 8) | tmp[5];
984 if (timestamp)
985 get_ms(timestamp);
986 return 0;
987}
988
995int mpu_get_accel_reg(short *data, unsigned long *timestamp)
996{
997 unsigned char tmp[6];
998
1000 return -1;
1001
1002 if (i2c_read(st.hw->addr, st.reg->raw_accel, 6, tmp))
1003 return -1;
1004 data[0] = (tmp[0] << 8) | tmp[1];
1005 data[1] = (tmp[2] << 8) | tmp[3];
1006 data[2] = (tmp[4] << 8) | tmp[5];
1007 if (timestamp)
1008 get_ms(timestamp);
1009 return 0;
1010}
1011
1018int mpu_get_temperature(long *data, unsigned long *timestamp)
1019{
1020 unsigned char tmp[2];
1021 short raw;
1022
1023 if (!(st.chip_cfg.sensors))
1024 return -1;
1025
1026 if (i2c_read(st.hw->addr, st.reg->temp, 2, tmp))
1027 return -1;
1028 raw = (tmp[0] << 8) | tmp[1];
1029 if (timestamp)
1030 get_ms(timestamp);
1031
1032 data[0] = (long)((35 + ((raw - (float)st.hw->temp_offset) / st.hw->temp_sens)) * 65536L);
1033 return 0;
1034}
1035
1043int mpu_set_accel_bias(const long *accel_bias)
1044{
1045 unsigned char data[6];
1046 short accel_hw[3];
1047 short got_accel[3];
1048 short fg[3];
1049
1050 if (!accel_bias)
1051 return -1;
1052 if (!accel_bias[0] && !accel_bias[1] && !accel_bias[2])
1053 return 0;
1054
1055 if (i2c_read(st.hw->addr, 3, 3, data))
1056 return -1;
1057 fg[0] = ((data[0] >> 4) + 8) & 0xf;
1058 fg[1] = ((data[1] >> 4) + 8) & 0xf;
1059 fg[2] = ((data[2] >> 4) + 8) & 0xf;
1060
1061 accel_hw[0] = (short)(accel_bias[0] * 2 / (64 + fg[0]));
1062 accel_hw[1] = (short)(accel_bias[1] * 2 / (64 + fg[1]));
1063 accel_hw[2] = (short)(accel_bias[2] * 2 / (64 + fg[2]));
1064
1065 if (i2c_read(st.hw->addr, 0x06, 6, data))
1066 return -1;
1067
1068 got_accel[0] = ((short)data[0] << 8) | data[1];
1069 got_accel[1] = ((short)data[2] << 8) | data[3];
1070 got_accel[2] = ((short)data[4] << 8) | data[5];
1071
1072 accel_hw[0] += got_accel[0];
1073 accel_hw[1] += got_accel[1];
1074 accel_hw[2] += got_accel[2];
1075
1076 data[0] = (accel_hw[0] >> 8) & 0xff;
1077 data[1] = (accel_hw[0]) & 0xff;
1078 data[2] = (accel_hw[1] >> 8) & 0xff;
1079 data[3] = (accel_hw[1]) & 0xff;
1080 data[4] = (accel_hw[2] >> 8) & 0xff;
1081 data[5] = (accel_hw[2]) & 0xff;
1082
1083 if (i2c_write(st.hw->addr, 0x06, 6, data))
1084 return -1;
1085 return 0;
1086}
1087
1093{
1094 unsigned char data;
1095
1096 if (!(st.chip_cfg.sensors))
1097 return -1;
1098
1099 data = 0;
1100 if (i2c_write(st.hw->addr, st.reg->int_enable, 1, &data))
1101 return -1;
1102 if (i2c_write(st.hw->addr, st.reg->fifo_en, 1, &data))
1103 return -1;
1104 if (i2c_write(st.hw->addr, st.reg->user_ctrl, 1, &data))
1105 return -1;
1106
1107 if (st.chip_cfg.dmp_on) {
1108 data = BIT_FIFO_RST | BIT_DMP_RST;
1109 if (i2c_write(st.hw->addr, st.reg->user_ctrl, 1, &data))
1110 return -1;
1111 delay_ms(50);
1112 data = BIT_DMP_EN | BIT_FIFO_EN;
1114 data |= BIT_AUX_IF_EN;
1115 if (i2c_write(st.hw->addr, st.reg->user_ctrl, 1, &data))
1116 return -1;
1118 data = BIT_DMP_INT_EN;
1119 else
1120 data = 0;
1121 if (i2c_write(st.hw->addr, st.reg->int_enable, 1, &data))
1122 return -1;
1123 data = 0;
1124 if (i2c_write(st.hw->addr, st.reg->fifo_en, 1, &data))
1125 return -1;
1126 } else {
1127 data = BIT_FIFO_RST;
1128 if (i2c_write(st.hw->addr, st.reg->user_ctrl, 1, &data))
1129 return -1;
1131 data = BIT_FIFO_EN;
1132 else
1133 data = BIT_FIFO_EN | BIT_AUX_IF_EN;
1134 if (i2c_write(st.hw->addr, st.reg->user_ctrl, 1, &data))
1135 return -1;
1136 delay_ms(50);
1138 data = BIT_DATA_RDY_EN;
1139 else
1140 data = 0;
1141 if (i2c_write(st.hw->addr, st.reg->int_enable, 1, &data))
1142 return -1;
1144 return -1;
1145 }
1146 return 0;
1147}
1148
1154int mpu_get_gyro_fsr(unsigned short *fsr)
1155{
1156 switch (st.chip_cfg.gyro_fsr) {
1157 case INV_FSR_250DPS:
1158 fsr[0] = 250;
1159 break;
1160 case INV_FSR_500DPS:
1161 fsr[0] = 500;
1162 break;
1163 case INV_FSR_1000DPS:
1164 fsr[0] = 1000;
1165 break;
1166 case INV_FSR_2000DPS:
1167 fsr[0] = 2000;
1168 break;
1169 default:
1170 fsr[0] = 0;
1171 break;
1172 }
1173 return 0;
1174}
1175
1181int mpu_set_gyro_fsr(unsigned short fsr)
1182{
1183 unsigned char data;
1184
1185 if (!(st.chip_cfg.sensors))
1186 return -1;
1187
1188 switch (fsr) {
1189 case 250:
1190 data = INV_FSR_250DPS << 3;
1191 break;
1192 case 500:
1193 data = INV_FSR_500DPS << 3;
1194 break;
1195 case 1000:
1196 data = INV_FSR_1000DPS << 3;
1197 break;
1198 case 2000:
1199 data = INV_FSR_2000DPS << 3;
1200 break;
1201 default:
1202 return -1;
1203 }
1204
1205 if (st.chip_cfg.gyro_fsr == (data >> 3))
1206 return 0;
1207 if (i2c_write(st.hw->addr, st.reg->gyro_cfg, 1, &data))
1208 return -1;
1209 st.chip_cfg.gyro_fsr = data >> 3;
1210 return 0;
1211}
1212
1218int mpu_get_accel_fsr(unsigned char *fsr)
1219{
1220 switch (st.chip_cfg.accel_fsr) {
1221 case INV_FSR_2G:
1222 fsr[0] = 2;
1223 break;
1224 case INV_FSR_4G:
1225 fsr[0] = 4;
1226 break;
1227 case INV_FSR_8G:
1228 fsr[0] = 8;
1229 break;
1230 case INV_FSR_16G:
1231 fsr[0] = 16;
1232 break;
1233 default:
1234 return -1;
1235 }
1237 fsr[0] <<= 1;
1238 return 0;
1239}
1240
1246int mpu_set_accel_fsr(unsigned char fsr)
1247{
1248 unsigned char data;
1249
1250 if (!(st.chip_cfg.sensors))
1251 return -1;
1252
1253 switch (fsr) {
1254 case 2:
1255 data = INV_FSR_2G << 3;
1256 break;
1257 case 4:
1258 data = INV_FSR_4G << 3;
1259 break;
1260 case 8:
1261 data = INV_FSR_8G << 3;
1262 break;
1263 case 16:
1264 data = INV_FSR_16G << 3;
1265 break;
1266 default:
1267 return -1;
1268 }
1269
1270 if (st.chip_cfg.accel_fsr == (data >> 3))
1271 return 0;
1272 if (i2c_write(st.hw->addr, st.reg->accel_cfg, 1, &data))
1273 return -1;
1274 st.chip_cfg.accel_fsr = data >> 3;
1275 return 0;
1276}
1277
1283int mpu_get_lpf(unsigned short *lpf)
1284{
1285 switch (st.chip_cfg.lpf) {
1286 case INV_FILTER_188HZ:
1287 lpf[0] = 188;
1288 break;
1289 case INV_FILTER_98HZ:
1290 lpf[0] = 98;
1291 break;
1292 case INV_FILTER_42HZ:
1293 lpf[0] = 42;
1294 break;
1295 case INV_FILTER_20HZ:
1296 lpf[0] = 20;
1297 break;
1298 case INV_FILTER_10HZ:
1299 lpf[0] = 10;
1300 break;
1301 case INV_FILTER_5HZ:
1302 lpf[0] = 5;
1303 break;
1306 default:
1307 lpf[0] = 0;
1308 break;
1309 }
1310 return 0;
1311}
1312
1319int mpu_set_lpf(unsigned short lpf)
1320{
1321 unsigned char data;
1322
1323 if (!(st.chip_cfg.sensors))
1324 return -1;
1325
1326 if (lpf >= 188)
1327 data = INV_FILTER_188HZ;
1328 else if (lpf >= 98)
1329 data = INV_FILTER_98HZ;
1330 else if (lpf >= 42)
1331 data = INV_FILTER_42HZ;
1332 else if (lpf >= 20)
1333 data = INV_FILTER_20HZ;
1334 else if (lpf >= 10)
1335 data = INV_FILTER_10HZ;
1336 else
1337 data = INV_FILTER_5HZ;
1338
1339 if (st.chip_cfg.lpf == data)
1340 return 0;
1341 if (i2c_write(st.hw->addr, st.reg->lpf, 1, &data))
1342 return -1;
1343 st.chip_cfg.lpf = data;
1344 return 0;
1345}
1346
1352int mpu_get_sample_rate(unsigned short *rate)
1353{
1354 if (st.chip_cfg.dmp_on)
1355 return -1;
1356 else
1357 rate[0] = st.chip_cfg.sample_rate;
1358 return 0;
1359}
1360
1367int mpu_set_sample_rate(unsigned short rate)
1368{
1369 unsigned char data;
1370
1371 if (!(st.chip_cfg.sensors))
1372 return -1;
1373
1374 if (st.chip_cfg.dmp_on)
1375 return -1;
1376 else {
1378 if (rate && (rate <= 40)) {
1379 /* Just stay in low-power accel mode. */
1380 mpu_lp_accel_mode(rate);
1381 return 0;
1382 }
1383 /* Requested rate exceeds the allowed frequencies in LP accel mode,
1384 * switch back to full-power mode.
1385 */
1387 }
1388 if (rate < 4)
1389 rate = 4;
1390 else if (rate > 1000)
1391 rate = 1000;
1392
1393 data = 1000 / rate - 1;
1394 if (i2c_write(st.hw->addr, st.reg->rate_div, 1, &data))
1395 return -1;
1396
1397 st.chip_cfg.sample_rate = 1000 / (1 + data);
1398
1399#ifdef AK89xx_SECONDARY
1400 mpu_set_compass_sample_rate(min(st.chip_cfg.compass_sample_rate, MAX_COMPASS_SAMPLE_RATE));
1401#endif
1402
1403 /* Automatically set LPF to 1/2 sampling rate. */
1405 return 0;
1406 }
1407}
1408
1414int mpu_get_compass_sample_rate(unsigned short *rate)
1415{
1416#ifdef AK89xx_SECONDARY
1417 rate[0] = st.chip_cfg.compass_sample_rate;
1418 return 0;
1419#else
1420 rate[0] = 0;
1421 return -1;
1422#endif
1423}
1424
1436int mpu_set_compass_sample_rate(unsigned short rate)
1437{
1438#ifdef AK89xx_SECONDARY
1439 unsigned char div;
1440 if (!rate || rate > st.chip_cfg.sample_rate || rate > MAX_COMPASS_SAMPLE_RATE)
1441 return -1;
1442
1443 div = st.chip_cfg.sample_rate / rate - 1;
1444 if (i2c_write(st.hw->addr, st.reg->s4_ctrl, 1, &div))
1445 return -1;
1446 st.chip_cfg.compass_sample_rate = st.chip_cfg.sample_rate / (div + 1);
1447 return 0;
1448#else
1449 return -1;
1450#endif
1451}
1452
1458int mpu_get_gyro_sens(float *sens)
1459{
1460 switch (st.chip_cfg.gyro_fsr) {
1461 case INV_FSR_250DPS:
1462 sens[0] = 131.f;
1463 break;
1464 case INV_FSR_500DPS:
1465 sens[0] = 65.5f;
1466 break;
1467 case INV_FSR_1000DPS:
1468 sens[0] = 32.8f;
1469 break;
1470 case INV_FSR_2000DPS:
1471 sens[0] = 16.4f;
1472 break;
1473 default:
1474 return -1;
1475 }
1476 return 0;
1477}
1478
1484int mpu_get_accel_sens(unsigned short *sens)
1485{
1486 switch (st.chip_cfg.accel_fsr) {
1487 case INV_FSR_2G:
1488 sens[0] = 16384;
1489 break;
1490 case INV_FSR_4G:
1491 sens[0] = 8092;
1492 break;
1493 case INV_FSR_8G:
1494 sens[0] = 4096;
1495 break;
1496 case INV_FSR_16G:
1497 sens[0] = 2048;
1498 break;
1499 default:
1500 return -1;
1501 }
1503 sens[0] >>= 1;
1504 return 0;
1505}
1506
1516int mpu_get_fifo_config(unsigned char *sensors)
1517{
1518 sensors[0] = st.chip_cfg.fifo_enable;
1519 return 0;
1520}
1521
1531int mpu_configure_fifo(unsigned char sensors)
1532{
1533 unsigned char prev;
1534 int result = 0;
1535
1536 /* Compass data isn't going into the FIFO. Stop trying. */
1537 sensors &= ~INV_XYZ_COMPASS;
1538
1539 if (st.chip_cfg.dmp_on)
1540 return 0;
1541 else {
1542 if (!(st.chip_cfg.sensors))
1543 return -1;
1544 prev = st.chip_cfg.fifo_enable;
1546 if (st.chip_cfg.fifo_enable != sensors)
1547 /* You're not getting what you asked for. Some sensors are
1548 * asleep.
1549 */
1550 result = -1;
1551 else
1552 result = 0;
1553 if (sensors || st.chip_cfg.lp_accel_mode)
1554 set_int_enable(1);
1555 else
1556 set_int_enable(0);
1557 if (sensors) {
1558 if (mpu_reset_fifo()) {
1559 st.chip_cfg.fifo_enable = prev;
1560 return -1;
1561 }
1562 }
1563 }
1564
1565 return result;
1566}
1567
1573int mpu_get_power_state(unsigned char *power_on)
1574{
1575 if (st.chip_cfg.sensors)
1576 power_on[0] = 1;
1577 else
1578 power_on[0] = 0;
1579 return 0;
1580}
1581
1592int mpu_set_sensors(unsigned char sensors)
1593{
1594 unsigned char data;
1595#ifdef AK89xx_SECONDARY
1596 unsigned char user_ctrl;
1597#endif
1598
1599 if (sensors & INV_XYZ_GYRO)
1600 data = INV_CLK_PLL;
1601 else if (sensors)
1602 data = 0;
1603 else
1604 data = BIT_SLEEP;
1605 if (i2c_write(st.hw->addr, st.reg->pwr_mgmt_1, 1, &data)) {
1606 st.chip_cfg.sensors = 0;
1607 return -1;
1608 }
1609 st.chip_cfg.clk_src = data & ~BIT_SLEEP;
1610
1611 data = 0;
1612 if (!(sensors & INV_X_GYRO))
1613 data |= BIT_STBY_XG;
1614 if (!(sensors & INV_Y_GYRO))
1615 data |= BIT_STBY_YG;
1616 if (!(sensors & INV_Z_GYRO))
1617 data |= BIT_STBY_ZG;
1618 if (!(sensors & INV_XYZ_ACCEL))
1619 data |= BIT_STBY_XYZA;
1620 if (i2c_write(st.hw->addr, st.reg->pwr_mgmt_2, 1, &data)) {
1621 st.chip_cfg.sensors = 0;
1622 return -1;
1623 }
1624
1625 if (sensors && (sensors != INV_XYZ_ACCEL))
1626 /* Latched interrupts only used in LP accel mode. */
1628
1629#ifdef AK89xx_SECONDARY
1630#ifdef AK89xx_BYPASS
1631 if (sensors & INV_XYZ_COMPASS)
1632 mpu_set_bypass(1);
1633 else
1634 mpu_set_bypass(0);
1635#else
1636 if (i2c_read(st.hw->addr, st.reg->user_ctrl, 1, &user_ctrl))
1637 return -1;
1638 /* Handle AKM power management. */
1639 if (sensors & INV_XYZ_COMPASS) {
1640 data = AKM_SINGLE_MEASUREMENT;
1641 user_ctrl |= BIT_AUX_IF_EN;
1642 } else {
1643 data = AKM_POWER_DOWN;
1644 user_ctrl &= ~BIT_AUX_IF_EN;
1645 }
1646 if (st.chip_cfg.dmp_on)
1647 user_ctrl |= BIT_DMP_EN;
1648 else
1649 user_ctrl &= ~BIT_DMP_EN;
1650 if (i2c_write(st.hw->addr, st.reg->s1_do, 1, &data))
1651 return -1;
1652 /* Enable/disable I2C master mode. */
1653 if (i2c_write(st.hw->addr, st.reg->user_ctrl, 1, &user_ctrl))
1654 return -1;
1655#endif
1656#endif
1657
1658 st.chip_cfg.sensors = sensors;
1660 delay_ms(50);
1661 return 0;
1662}
1663
1669int mpu_get_int_status(short *status)
1670{
1671 unsigned char tmp[2];
1672 if (!st.chip_cfg.sensors)
1673 return -1;
1674 if (i2c_read(st.hw->addr, st.reg->dmp_int_status, 2, tmp))
1675 return -1;
1676 status[0] = (tmp[0] << 8) | tmp[1];
1677 return 0;
1678}
1679
1698int mpu_read_fifo(short *gyro, short *accel, unsigned long *timestamp,
1699 unsigned char *sensors, unsigned char *more)
1700{
1701 /* Assumes maximum packet size is gyro (6) + accel (6). */
1702 unsigned char data[MAX_PACKET_LENGTH];
1703 unsigned char packet_size = 0;
1704 unsigned short fifo_count, index = 0;
1705
1706 if (st.chip_cfg.dmp_on)
1707 return -1;
1708
1709 sensors[0] = 0;
1710 if (!st.chip_cfg.sensors)
1711 return -1;
1712 if (!st.chip_cfg.fifo_enable)
1713 return -1;
1714
1716 packet_size += 2;
1718 packet_size += 2;
1720 packet_size += 2;
1722 packet_size += 6;
1723
1724 if (i2c_read(st.hw->addr, st.reg->fifo_count_h, 2, data))
1725 return -1;
1726 fifo_count = (data[0] << 8) | data[1];
1727 if (fifo_count < packet_size)
1728 return 0;
1729// log_i("FIFO count: %hd\n", fifo_count);
1730 if (fifo_count > (st.hw->max_fifo >> 1)) {
1731 /* FIFO is 50% full, better check overflow bit. */
1732 if (i2c_read(st.hw->addr, st.reg->int_status, 1, data))
1733 return -1;
1734 if (data[0] & BIT_FIFO_OVERFLOW) {
1736 return -2;
1737 }
1738 }
1739 get_ms((unsigned long*)timestamp);
1740
1741 if (i2c_read(st.hw->addr, st.reg->fifo_r_w, packet_size, data))
1742 return -1;
1743 more[0] = fifo_count / packet_size - 1;
1744 sensors[0] = 0;
1745
1746 if ((index != packet_size) && st.chip_cfg.fifo_enable & INV_XYZ_ACCEL) {
1747 accel[0] = (data[index+0] << 8) | data[index+1];
1748 accel[1] = (data[index+2] << 8) | data[index+3];
1749 accel[2] = (data[index+4] << 8) | data[index+5];
1750 sensors[0] |= INV_XYZ_ACCEL;
1751 index += 6;
1752 }
1753 if ((index != packet_size) && st.chip_cfg.fifo_enable & INV_X_GYRO) {
1754 gyro[0] = (data[index+0] << 8) | data[index+1];
1755 sensors[0] |= INV_X_GYRO;
1756 index += 2;
1757 }
1758 if ((index != packet_size) && st.chip_cfg.fifo_enable & INV_Y_GYRO) {
1759 gyro[1] = (data[index+0] << 8) | data[index+1];
1760 sensors[0] |= INV_Y_GYRO;
1761 index += 2;
1762 }
1763 if ((index != packet_size) && st.chip_cfg.fifo_enable & INV_Z_GYRO) {
1764 gyro[2] = (data[index+0] << 8) | data[index+1];
1765 sensors[0] |= INV_Z_GYRO;
1766 index += 2;
1767 }
1768
1769 return 0;
1770}
1771
1779int mpu_read_fifo_stream(unsigned short length, unsigned char *data,
1780 unsigned char *more)
1781{
1782 unsigned char tmp[2];
1783 unsigned short fifo_count;
1784 if (!st.chip_cfg.dmp_on)
1785 return -1;
1786 if (!st.chip_cfg.sensors)
1787 return -1;
1788
1789 if (i2c_read(st.hw->addr, st.reg->fifo_count_h, 2, tmp))
1790 return -1;
1791 fifo_count = (tmp[0] << 8) | tmp[1];
1792 if (fifo_count < length) {
1793 more[0] = 0;
1794 return -1;
1795 }
1796 if (fifo_count > (st.hw->max_fifo >> 1)) {
1797 /* FIFO is 50% full, better check overflow bit. */
1798 if (i2c_read(st.hw->addr, st.reg->int_status, 1, tmp))
1799 return -1;
1800 if (tmp[0] & BIT_FIFO_OVERFLOW) {
1802 return -2;
1803 }
1804 }
1805
1806 if (i2c_read(st.hw->addr, st.reg->fifo_r_w, length, data))
1807 return -1;
1808 more[0] = fifo_count / length - 1;
1809 return 0;
1810}
1811
1817int mpu_set_bypass(unsigned char bypass_on)
1818{
1819 unsigned char tmp;
1820
1821 if (st.chip_cfg.bypass_mode == bypass_on)
1822 return 0;
1823
1824 if (bypass_on) {
1825 if (i2c_read(st.hw->addr, st.reg->user_ctrl, 1, &tmp))
1826 return -1;
1827 tmp &= ~BIT_AUX_IF_EN;
1828 if (i2c_write(st.hw->addr, st.reg->user_ctrl, 1, &tmp))
1829 return -1;
1830 delay_ms(3);
1831 tmp = BIT_BYPASS_EN;
1833 tmp |= BIT_ACTL;
1836 if (i2c_write(st.hw->addr, st.reg->int_pin_cfg, 1, &tmp))
1837 return -1;
1838 } else {
1839 /* Enable I2C master mode if compass is being used. */
1840 if (i2c_read(st.hw->addr, st.reg->user_ctrl, 1, &tmp))
1841 return -1;
1843 tmp |= BIT_AUX_IF_EN;
1844 else
1845 tmp &= ~BIT_AUX_IF_EN;
1846 if (i2c_write(st.hw->addr, st.reg->user_ctrl, 1, &tmp))
1847 return -1;
1848 delay_ms(3);
1850 tmp = BIT_ACTL;
1851 else
1852 tmp = 0;
1855 if (i2c_write(st.hw->addr, st.reg->int_pin_cfg, 1, &tmp))
1856 return -1;
1857 }
1858 st.chip_cfg.bypass_mode = bypass_on;
1859 return 0;
1860}
1861
1867int mpu_set_int_level(unsigned char active_low)
1868{
1869 st.chip_cfg.active_low_int = active_low;
1870 return 0;
1871}
1872
1879int mpu_set_int_latched(unsigned char enable)
1880{
1881 unsigned char tmp;
1882 if (st.chip_cfg.latched_int == enable)
1883 return 0;
1884
1885 if (enable)
1887 else
1888 tmp = 0;
1890 tmp |= BIT_BYPASS_EN;
1892 tmp |= BIT_ACTL;
1893 if (i2c_write(st.hw->addr, st.reg->int_pin_cfg, 1, &tmp))
1894 return -1;
1895 st.chip_cfg.latched_int = enable;
1896 return 0;
1897}
1898
1899#ifdef MPU6050
1900static int get_accel_prod_shift(float *st_shift)
1901{
1902 unsigned char tmp[4], shift_code[3], ii;
1903
1904 if (i2c_read(st.hw->addr, 0x0D, 4, tmp))
1905 return 0x07;
1906
1907 shift_code[0] = ((tmp[0] & 0xE0) >> 3) | ((tmp[3] & 0x30) >> 4);
1908 shift_code[1] = ((tmp[1] & 0xE0) >> 3) | ((tmp[3] & 0x0C) >> 2);
1909 shift_code[2] = ((tmp[2] & 0xE0) >> 3) | (tmp[3] & 0x03);
1910 for (ii = 0; ii < 3; ii++) {
1911 if (!shift_code[ii]) {
1912 st_shift[ii] = 0.f;
1913 continue;
1914 }
1915 /* Equivalent to..
1916 * st_shift[ii] = 0.34f * powf(0.92f/0.34f, (shift_code[ii]-1) / 30.f)
1917 */
1918 st_shift[ii] = 0.34f;
1919 while (--shift_code[ii])
1920 st_shift[ii] *= 1.034f;
1921 }
1922 return 0;
1923}
1924
1925static int accel_self_test(long *bias_regular, long *bias_st)
1926{
1927 int jj, result = 0;
1928 float st_shift[3], st_shift_cust, st_shift_var;
1929
1930 get_accel_prod_shift(st_shift);
1931 for(jj = 0; jj < 3; jj++) {
1932 st_shift_cust = labs(bias_regular[jj] - bias_st[jj]) / 65536.f;
1933 if (st_shift[jj]) {
1934 st_shift_var = st_shift_cust / st_shift[jj] - 1.f;
1935 if (fabs(st_shift_var) > test.max_accel_var)
1936 result |= 1 << jj;
1937 } else if ((st_shift_cust < test.min_g) ||
1938 (st_shift_cust > test.max_g))
1939 result |= 1 << jj;
1940 }
1941
1942 return result;
1943}
1944
1945static int gyro_self_test(long *bias_regular, long *bias_st)
1946{
1947 int jj, result = 0;
1948 unsigned char tmp[3];
1949 float st_shift, st_shift_cust, st_shift_var;
1950
1951 if (i2c_read(st.hw->addr, 0x0D, 3, tmp))
1952 return 0x07;
1953
1954 tmp[0] &= 0x1F;
1955 tmp[1] &= 0x1F;
1956 tmp[2] &= 0x1F;
1957
1958 for (jj = 0; jj < 3; jj++) {
1959 st_shift_cust = labs(bias_regular[jj] - bias_st[jj]) / 65536.f;
1960 if (tmp[jj]) {
1961 st_shift = 3275.f / test.gyro_sens;
1962 while (--tmp[jj])
1963 st_shift *= 1.046f;
1964 st_shift_var = st_shift_cust / st_shift - 1.f;
1965 if (fabs(st_shift_var) > test.max_gyro_var)
1966 result |= 1 << jj;
1967 } else if ((st_shift_cust < test.min_dps) ||
1968 (st_shift_cust > test.max_dps))
1969 result |= 1 << jj;
1970 }
1971 return result;
1972}
1973
1974#ifdef AK89xx_SECONDARY
1975static int compass_self_test(void)
1976{
1977 unsigned char tmp[6];
1978 unsigned char tries = 10;
1979 int result = 0x07;
1980 short data;
1981
1982 mpu_set_bypass(1);
1983
1984 tmp[0] = AKM_POWER_DOWN;
1985 if (i2c_write(st.chip_cfg.compass_addr, AKM_REG_CNTL, 1, tmp))
1986 return 0x07;
1987 tmp[0] = AKM_BIT_SELF_TEST;
1988 if (i2c_write(st.chip_cfg.compass_addr, AKM_REG_ASTC, 1, tmp))
1989 goto AKM_restore;
1990 tmp[0] = AKM_MODE_SELF_TEST;
1991 if (i2c_write(st.chip_cfg.compass_addr, AKM_REG_CNTL, 1, tmp))
1992 goto AKM_restore;
1993
1994 do {
1995 delay_ms(10);
1996 if (i2c_read(st.chip_cfg.compass_addr, AKM_REG_ST1, 1, tmp))
1997 goto AKM_restore;
1998 if (tmp[0] & AKM_DATA_READY)
1999 break;
2000 } while (tries--);
2001 if (!(tmp[0] & AKM_DATA_READY))
2002 goto AKM_restore;
2003
2004 if (i2c_read(st.chip_cfg.compass_addr, AKM_REG_HXL, 6, tmp))
2005 goto AKM_restore;
2006
2007 result = 0;
2008 data = (short)(tmp[1] << 8) | tmp[0];
2009 if ((data > 100) || (data < -100))
2010 result |= 0x01;
2011 data = (short)(tmp[3] << 8) | tmp[2];
2012 if ((data > 100) || (data < -100))
2013 result |= 0x02;
2014 data = (short)(tmp[5] << 8) | tmp[4];
2015 if ((data > -300) || (data < -1000))
2016 result |= 0x04;
2017
2018AKM_restore:
2019 tmp[0] = 0 | SUPPORTS_AK89xx_HIGH_SENS;
2020 i2c_write(st.chip_cfg.compass_addr, AKM_REG_ASTC, 1, tmp);
2021 tmp[0] = SUPPORTS_AK89xx_HIGH_SENS;
2022 i2c_write(st.chip_cfg.compass_addr, AKM_REG_CNTL, 1, tmp);
2023 mpu_set_bypass(0);
2024 return result;
2025}
2026#endif
2027#endif
2028
2029static int get_st_biases(long *gyro, long *accel, unsigned char hw_test)
2030{
2031 unsigned char data[MAX_PACKET_LENGTH];
2032 unsigned char packet_count, ii;
2033 unsigned short fifo_count;
2034
2035 data[0] = 0x01;
2036 data[1] = 0;
2037 if (i2c_write(st.hw->addr, st.reg->pwr_mgmt_1, 2, data))
2038 return -1;
2039 delay_ms(200);
2040 data[0] = 0;
2041 if (i2c_write(st.hw->addr, st.reg->int_enable, 1, data))
2042 return -1;
2043 if (i2c_write(st.hw->addr, st.reg->fifo_en, 1, data))
2044 return -1;
2045 if (i2c_write(st.hw->addr, st.reg->pwr_mgmt_1, 1, data))
2046 return -1;
2047 if (i2c_write(st.hw->addr, st.reg->i2c_mst, 1, data))
2048 return -1;
2049 if (i2c_write(st.hw->addr, st.reg->user_ctrl, 1, data))
2050 return -1;
2051 data[0] = BIT_FIFO_RST | BIT_DMP_RST;
2052 if (i2c_write(st.hw->addr, st.reg->user_ctrl, 1, data))
2053 return -1;
2054 delay_ms(15);
2055 data[0] = st.test->reg_lpf;
2056 if (i2c_write(st.hw->addr, st.reg->lpf, 1, data))
2057 return -1;
2058 data[0] = st.test->reg_rate_div;
2059 if (i2c_write(st.hw->addr, st.reg->rate_div, 1, data))
2060 return -1;
2061 if (hw_test)
2062 data[0] = st.test->reg_gyro_fsr | 0xE0;
2063 else
2064 data[0] = st.test->reg_gyro_fsr;
2065 if (i2c_write(st.hw->addr, st.reg->gyro_cfg, 1, data))
2066 return -1;
2067
2068 if (hw_test)
2069 data[0] = st.test->reg_accel_fsr | 0xE0;
2070 else
2071 data[0] = test.reg_accel_fsr;
2072 if (i2c_write(st.hw->addr, st.reg->accel_cfg, 1, data))
2073 return -1;
2074 if (hw_test)
2075 delay_ms(200);
2076
2077 /* Fill FIFO for test.wait_ms milliseconds. */
2078 data[0] = BIT_FIFO_EN;
2079 if (i2c_write(st.hw->addr, st.reg->user_ctrl, 1, data))
2080 return -1;
2081
2082 data[0] = INV_XYZ_GYRO | INV_XYZ_ACCEL;
2083 if (i2c_write(st.hw->addr, st.reg->fifo_en, 1, data))
2084 return -1;
2086 data[0] = 0;
2087 if (i2c_write(st.hw->addr, st.reg->fifo_en, 1, data))
2088 return -1;
2089
2090 if (i2c_read(st.hw->addr, st.reg->fifo_count_h, 2, data))
2091 return -1;
2092
2093 fifo_count = (data[0] << 8) | data[1];
2094 packet_count = fifo_count / MAX_PACKET_LENGTH;
2095 gyro[0] = gyro[1] = gyro[2] = 0;
2096 accel[0] = accel[1] = accel[2] = 0;
2097
2098 for (ii = 0; ii < packet_count; ii++) {
2099 short accel_cur[3], gyro_cur[3];
2101 return -1;
2102 accel_cur[0] = ((short)data[0] << 8) | data[1];
2103 accel_cur[1] = ((short)data[2] << 8) | data[3];
2104 accel_cur[2] = ((short)data[4] << 8) | data[5];
2105 accel[0] += (long)accel_cur[0];
2106 accel[1] += (long)accel_cur[1];
2107 accel[2] += (long)accel_cur[2];
2108 gyro_cur[0] = (((short)data[6] << 8) | data[7]);
2109 gyro_cur[1] = (((short)data[8] << 8) | data[9]);
2110 gyro_cur[2] = (((short)data[10] << 8) | data[11]);
2111 gyro[0] += (long)gyro_cur[0];
2112 gyro[1] += (long)gyro_cur[1];
2113 gyro[2] += (long)gyro_cur[2];
2114 }
2115#ifdef EMPL_NO_64BIT
2116 gyro[0] = (long)(((float)gyro[0]*65536.f) / test.gyro_sens / packet_count);
2117 gyro[1] = (long)(((float)gyro[1]*65536.f) / test.gyro_sens / packet_count);
2118 gyro[2] = (long)(((float)gyro[2]*65536.f) / test.gyro_sens / packet_count);
2119 if (has_accel) {
2120 accel[0] = (long)(((float)accel[0]*65536.f) / test.accel_sens /
2121 packet_count);
2122 accel[1] = (long)(((float)accel[1]*65536.f) / test.accel_sens /
2123 packet_count);
2124 accel[2] = (long)(((float)accel[2]*65536.f) / test.accel_sens /
2125 packet_count);
2126 /* Don't remove gravity! */
2127 accel[2] -= 65536L;
2128 }
2129#else
2130 gyro[0] = (long)(((long long)gyro[0]<<16) / test.gyro_sens / packet_count);
2131 gyro[1] = (long)(((long long)gyro[1]<<16) / test.gyro_sens / packet_count);
2132 gyro[2] = (long)(((long long)gyro[2]<<16) / test.gyro_sens / packet_count);
2133 accel[0] = (long)(((long long)accel[0]<<16) / test.accel_sens /
2134 packet_count);
2135 accel[1] = (long)(((long long)accel[1]<<16) / test.accel_sens /
2136 packet_count);
2137 accel[2] = (long)(((long long)accel[2]<<16) / test.accel_sens /
2138 packet_count);
2139 /* Don't remove gravity! */
2140 if (accel[2] > 0L)
2141 accel[2] -= 65536L;
2142 else
2143 accel[2] += 65536L;
2144#endif
2145
2146 return 0;
2147}
2148
2169int mpu_run_self_test(long *gyro, long *accel)
2170{
2171#ifdef MPU6050
2172 const unsigned char tries = 2;
2173 long gyro_st[3], accel_st[3];
2174 unsigned char accel_result, gyro_result;
2175#ifdef AK89xx_SECONDARY
2176 unsigned char compass_result;
2177#endif
2178 int ii;
2179#endif
2180 int result;
2181 unsigned char accel_fsr, fifo_sensors, sensors_on;
2182 unsigned short gyro_fsr, sample_rate, lpf;
2183 unsigned char dmp_was_on;
2184
2185 if (st.chip_cfg.dmp_on) {
2187 dmp_was_on = 1;
2188 } else
2189 dmp_was_on = 0;
2190
2191 /* Get initial settings. */
2192 mpu_get_gyro_fsr(&gyro_fsr);
2193 mpu_get_accel_fsr(&accel_fsr);
2194 mpu_get_lpf(&lpf);
2195 mpu_get_sample_rate(&sample_rate);
2196 sensors_on = st.chip_cfg.sensors;
2197 mpu_get_fifo_config(&fifo_sensors);
2198
2199 /* For older chips, the self-test will be different. */
2200#if defined MPU6050
2201 for (ii = 0; ii < tries; ii++)
2202 if (!get_st_biases(gyro, accel, 0))
2203 break;
2204 if (ii == tries) {
2205 /* If we reach this point, we most likely encountered an I2C error.
2206 * We'll just report an error for all three sensors.
2207 */
2208 result = 0;
2209 goto restore;
2210 }
2211 for (ii = 0; ii < tries; ii++)
2212 if (!get_st_biases(gyro_st, accel_st, 1))
2213 break;
2214 if (ii == tries) {
2215 /* Again, probably an I2C error. */
2216 result = 0;
2217 goto restore;
2218 }
2219 accel_result = accel_self_test(accel, accel_st);
2220 gyro_result = gyro_self_test(gyro, gyro_st);
2221
2222 result = 0;
2223 if (!gyro_result)
2224 result |= 0x01;
2225 if (!accel_result)
2226 result |= 0x02;
2227
2228#ifdef AK89xx_SECONDARY
2229 compass_result = compass_self_test();
2230 if (!compass_result)
2231 result |= 0x04;
2232#endif
2233restore:
2234#elif defined MPU6500
2235 /* For now, this function will return a "pass" result for all three sensors
2236 * for compatibility with current test applications.
2237 */
2238 get_st_biases(gyro, accel, 0);
2239 result = 0x7;
2240#endif
2241 /* Set to invalid values to ensure no I2C writes are skipped. */
2242 st.chip_cfg.gyro_fsr = 0xFF;
2243 st.chip_cfg.accel_fsr = 0xFF;
2244 st.chip_cfg.lpf = 0xFF;
2245 st.chip_cfg.sample_rate = 0xFFFF;
2246 st.chip_cfg.sensors = 0xFF;
2247 st.chip_cfg.fifo_enable = 0xFF;
2249 mpu_set_gyro_fsr(gyro_fsr);
2250 mpu_set_accel_fsr(accel_fsr);
2251 mpu_set_lpf(lpf);
2252 mpu_set_sample_rate(sample_rate);
2253 mpu_set_sensors(sensors_on);
2254 mpu_configure_fifo(fifo_sensors);
2255
2256 if (dmp_was_on)
2258
2259 return result;
2260}
2261
2271int mpu_write_mem(unsigned short mem_addr, unsigned short length,
2272 unsigned char *data)
2273{
2274 unsigned char tmp[2];
2275
2276 if (!data)
2277 return -1;
2278 if (!st.chip_cfg.sensors)
2279 return -1;
2280
2281 tmp[0] = (unsigned char)(mem_addr >> 8);
2282 tmp[1] = (unsigned char)(mem_addr & 0xFF);
2283
2284 /* Check bank boundaries. */
2285 if (tmp[1] + length > st.hw->bank_size)
2286 return -1;
2287
2288 if (i2c_write(st.hw->addr, st.reg->bank_sel, 2, tmp))
2289 return -1;
2290 if (i2c_write(st.hw->addr, st.reg->mem_r_w, length, data))
2291 return -1;
2292 return 0;
2293}
2294
2304int mpu_read_mem(unsigned short mem_addr, unsigned short length,
2305 unsigned char *data)
2306{
2307 unsigned char tmp[2];
2308
2309 if (!data)
2310 return -1;
2311 if (!st.chip_cfg.sensors)
2312 return -1;
2313
2314 tmp[0] = (unsigned char)(mem_addr >> 8);
2315 tmp[1] = (unsigned char)(mem_addr & 0xFF);
2316
2317 /* Check bank boundaries. */
2318 if (tmp[1] + length > st.hw->bank_size)
2319 return -1;
2320
2321 if (i2c_write(st.hw->addr, st.reg->bank_sel, 2, tmp))
2322 return -1;
2323 if (i2c_read(st.hw->addr, st.reg->mem_r_w, length, data))
2324 return -1;
2325 return 0;
2326}
2327
2336int mpu_load_firmware(unsigned short length, const unsigned char *firmware,
2337 unsigned short start_addr, unsigned short sample_rate)
2338{
2339 unsigned short ii;
2340 unsigned short this_write;
2341 /* Must divide evenly into st.hw->bank_size to avoid bank crossings. */
2342#define LOAD_CHUNK (16)
2343 unsigned char cur[LOAD_CHUNK], tmp[2];
2344
2346 /* DMP should only be loaded once. */
2347 return -1;
2348
2349 if (!firmware)
2350 return -1;
2351 for (ii = 0; ii < length; ii += this_write) {
2352 this_write = min(LOAD_CHUNK, length - ii);
2353 if (mpu_write_mem(ii, this_write, (unsigned char*)&firmware[ii]))
2354 return -1;
2355 if (mpu_read_mem(ii, this_write, cur))
2356 return -1;
2357 if (memcmp(firmware+ii, cur, this_write))
2358 return -2;
2359 }
2360
2361 /* Set program start address. */
2362 tmp[0] = start_addr >> 8;
2363 tmp[1] = start_addr & 0xFF;
2364 if (i2c_write(st.hw->addr, st.reg->prgm_start_h, 2, tmp))
2365 return -1;
2366
2368 st.chip_cfg.dmp_sample_rate = sample_rate;
2369 return 0;
2370}
2371
2377int mpu_set_dmp_state(unsigned char enable)
2378{
2379 unsigned char tmp;
2380 if (st.chip_cfg.dmp_on == enable)
2381 return 0;
2382
2383 if (enable) {
2384 if (!st.chip_cfg.dmp_loaded)
2385 return -1;
2386 /* Disable data ready interrupt. */
2387 set_int_enable(0);
2388 /* Disable bypass mode. */
2389 mpu_set_bypass(0);
2390 /* Keep constant sample rate, FIFO rate controlled by DMP. */
2392 /* Remove FIFO elements. */
2393 tmp = 0;
2394 i2c_write(st.hw->addr, 0x23, 1, &tmp);
2395 st.chip_cfg.dmp_on = 1;
2396 /* Enable DMP interrupt. */
2397 set_int_enable(1);
2399 } else {
2400 /* Disable DMP interrupt. */
2401 set_int_enable(0);
2402 /* Restore FIFO settings. */
2403 tmp = st.chip_cfg.fifo_enable;
2404 i2c_write(st.hw->addr, 0x23, 1, &tmp);
2405 st.chip_cfg.dmp_on = 0;
2407 }
2408 return 0;
2409}
2410
2416int mpu_get_dmp_state(unsigned char *enabled)
2417{
2418 enabled[0] = st.chip_cfg.dmp_on;
2419 return 0;
2420}
2421
2422
2423/* This initialization is similar to the one in ak8975.c. */
2425{
2426#ifdef AK89xx_SECONDARY
2427 unsigned char data[4], akm_addr;
2428
2429 mpu_set_bypass(1);
2430
2431 /* Find compass. Possible addresses range from 0x0C to 0x0F. */
2432 for (akm_addr = 0x0C; akm_addr <= 0x0F; akm_addr++) {
2433 int result;
2434 result = i2c_read(akm_addr, AKM_REG_WHOAMI, 1, data);
2435 if (!result && (data[0] == AKM_WHOAMI))
2436 break;
2437 }
2438
2439 if (akm_addr > 0x0F) {
2440 /* TODO: Handle this case in all compass-related functions. */
2441 log_e("Compass not found.\n");
2442 return -1;
2443 }
2444
2445 st.chip_cfg.compass_addr = akm_addr;
2446
2447 data[0] = AKM_POWER_DOWN;
2448 if (i2c_write(st.chip_cfg.compass_addr, AKM_REG_CNTL, 1, data))
2449 return -1;
2450 delay_ms(1);
2451
2452 data[0] = AKM_FUSE_ROM_ACCESS;
2453 if (i2c_write(st.chip_cfg.compass_addr, AKM_REG_CNTL, 1, data))
2454 return -1;
2455 delay_ms(1);
2456
2457 /* Get sensitivity adjustment data from fuse ROM. */
2458 if (i2c_read(st.chip_cfg.compass_addr, AKM_REG_ASAX, 3, data))
2459 return -1;
2460 st.chip_cfg.mag_sens_adj[0] = (long)data[0] + 128;
2461 st.chip_cfg.mag_sens_adj[1] = (long)data[1] + 128;
2462 st.chip_cfg.mag_sens_adj[2] = (long)data[2] + 128;
2463
2464 data[0] = AKM_POWER_DOWN;
2465 if (i2c_write(st.chip_cfg.compass_addr, AKM_REG_CNTL, 1, data))
2466 return -1;
2467 delay_ms(1);
2468
2469 mpu_set_bypass(0);
2470
2471 /* Set up master mode, master clock, and ES bit. */
2472 data[0] = 0x40;
2473 if (i2c_write(st.hw->addr, st.reg->i2c_mst, 1, data))
2474 return -1;
2475
2476 /* Slave 0 reads from AKM data registers. */
2477 data[0] = BIT_I2C_READ | st.chip_cfg.compass_addr;
2478 if (i2c_write(st.hw->addr, st.reg->s0_addr, 1, data))
2479 return -1;
2480
2481 /* Compass reads start at this register. */
2482 data[0] = AKM_REG_ST1;
2483 if (i2c_write(st.hw->addr, st.reg->s0_reg, 1, data))
2484 return -1;
2485
2486 /* Enable slave 0, 8-byte reads. */
2487 data[0] = BIT_SLAVE_EN | 8;
2488 if (i2c_write(st.hw->addr, st.reg->s0_ctrl, 1, data))
2489 return -1;
2490
2491 /* Slave 1 changes AKM measurement mode. */
2492 data[0] = st.chip_cfg.compass_addr;
2493 if (i2c_write(st.hw->addr, st.reg->s1_addr, 1, data))
2494 return -1;
2495
2496 /* AKM measurement mode register. */
2497 data[0] = AKM_REG_CNTL;
2498 if (i2c_write(st.hw->addr, st.reg->s1_reg, 1, data))
2499 return -1;
2500
2501 /* Enable slave 1, 1-byte writes. */
2502 data[0] = BIT_SLAVE_EN | 1;
2503 if (i2c_write(st.hw->addr, st.reg->s1_ctrl, 1, data))
2504 return -1;
2505
2506 /* Set slave 1 data. */
2507 data[0] = AKM_SINGLE_MEASUREMENT;
2508 if (i2c_write(st.hw->addr, st.reg->s1_do, 1, data))
2509 return -1;
2510
2511 /* Trigger slave 0 and slave 1 actions at each sample. */
2512 data[0] = 0x03;
2513 if (i2c_write(st.hw->addr, st.reg->i2c_delay_ctrl, 1, data))
2514 return -1;
2515
2516#ifdef MPU9150
2517 /* For the MPU9150, the auxiliary I2C bus needs to be set to VDD. */
2518 data[0] = BIT_I2C_MST_VDDIO;
2519 if (i2c_write(st.hw->addr, st.reg->yg_offs_tc, 1, data))
2520 return -1;
2521#endif
2522
2523 return 0;
2524#else
2525 return -1;
2526#endif
2527}
2528
2535int mpu_get_compass_reg(short *data, unsigned long *timestamp)
2536{
2537#ifdef AK89xx_SECONDARY
2538 unsigned char tmp[9];
2539
2541 return -1;
2542
2543#ifdef AK89xx_BYPASS
2544 if (i2c_read(st.chip_cfg.compass_addr, AKM_REG_ST1, 8, tmp))
2545 return -1;
2546 tmp[8] = AKM_SINGLE_MEASUREMENT;
2547 if (i2c_write(st.chip_cfg.compass_addr, AKM_REG_CNTL, 1, tmp+8))
2548 return -1;
2549#else
2550 if (i2c_read(st.hw->addr, st.reg->raw_compass, 8, tmp))
2551 return -1;
2552#endif
2553
2554#if defined AK8975_SECONDARY
2555 /* AK8975 doesn't have the overrun error bit. */
2556 if (!(tmp[0] & AKM_DATA_READY))
2557 return -2;
2558 if ((tmp[7] & AKM_OVERFLOW) || (tmp[7] & AKM_DATA_ERROR))
2559 return -3;
2560#elif defined AK8963_SECONDARY
2561 /* AK8963 doesn't have the data read error bit. */
2562 if (!(tmp[0] & AKM_DATA_READY) || (tmp[0] & AKM_DATA_OVERRUN))
2563 return -2;
2564 if (tmp[7] & AKM_OVERFLOW)
2565 return -3;
2566#endif
2567 data[0] = (tmp[2] << 8) | tmp[1];
2568 data[1] = (tmp[4] << 8) | tmp[3];
2569 data[2] = (tmp[6] << 8) | tmp[5];
2570
2571 data[0] = ((long)data[0] * st.chip_cfg.mag_sens_adj[0]) >> 8;
2572 data[1] = ((long)data[1] * st.chip_cfg.mag_sens_adj[1]) >> 8;
2573 data[2] = ((long)data[2] * st.chip_cfg.mag_sens_adj[2]) >> 8;
2574
2575 if (timestamp)
2576 get_ms(timestamp);
2577 return 0;
2578#else
2579 return -1;
2580#endif
2581}
2582
2588int mpu_get_compass_fsr(unsigned short *fsr)
2589{
2590#ifdef AK89xx_SECONDARY
2591 fsr[0] = st.hw->compass_fsr;
2592 return 0;
2593#else
2594 return -1;
2595#endif
2596}
2597
2642int mpu_lp_motion_interrupt(unsigned short thresh, unsigned char time,
2643 unsigned char lpa_freq)
2644{
2645 unsigned char data[3];
2646
2647 if (lpa_freq) {
2648 unsigned char thresh_hw;
2649
2650#if defined MPU6050
2651 /* TODO: Make these const/#defines. */
2652 /* 1LSb = 32mg. */
2653 if (thresh > 8160)
2654 thresh_hw = 255;
2655 else if (thresh < 32)
2656 thresh_hw = 1;
2657 else
2658 thresh_hw = thresh >> 5;
2659#elif defined MPU6500
2660 /* 1LSb = 4mg. */
2661 if (thresh > 1020)
2662 thresh_hw = 255;
2663 else if (thresh < 4)
2664 thresh_hw = 1;
2665 else
2666 thresh_hw = thresh >> 2;
2667#endif
2668
2669 if (!time)
2670 /* Minimum duration must be 1ms. */
2671 time = 1;
2672
2673#if defined MPU6050
2674 if (lpa_freq > 40)
2675#elif defined MPU6500
2676 if (lpa_freq > 640)
2677#endif
2678 /* At this point, the chip has not been re-configured, so the
2679 * function can safely exit.
2680 */
2681 return -1;
2682
2684 /* Store current settings for later. */
2685 if (st.chip_cfg.dmp_on) {
2687 st.chip_cfg.cache.dmp_on = 1;
2688 } else
2689 st.chip_cfg.cache.dmp_on = 0;
2696 }
2697
2698#ifdef MPU6050
2699 /* Disable hardware interrupts for now. */
2700 set_int_enable(0);
2701
2702 /* Enter full-power accel-only mode. */
2704
2705 /* Override current LPF (and HPF) settings to obtain a valid accel
2706 * reading.
2707 */
2708 data[0] = INV_FILTER_256HZ_NOLPF2;
2709 if (i2c_write(st.hw->addr, st.reg->lpf, 1, data))
2710 return -1;
2711
2712 /* NOTE: Digital high pass filter should be configured here. Since this
2713 * driver doesn't modify those bits anywhere, they should already be
2714 * cleared by default.
2715 */
2716
2717 /* Configure the device to send motion interrupts. */
2718 /* Enable motion interrupt. */
2719 data[0] = BIT_MOT_INT_EN;
2720 if (i2c_write(st.hw->addr, st.reg->int_enable, 1, data))
2721 goto lp_int_restore;
2722
2723 /* Set motion interrupt parameters. */
2724 data[0] = thresh_hw;
2725 data[1] = time;
2726 if (i2c_write(st.hw->addr, st.reg->motion_thr, 2, data))
2727 goto lp_int_restore;
2728
2729 /* Force hardware to "lock" current accel sample. */
2730 delay_ms(5);
2731 data[0] = (st.chip_cfg.accel_fsr << 3) | BITS_HPF;
2732 if (i2c_write(st.hw->addr, st.reg->accel_cfg, 1, data))
2733 goto lp_int_restore;
2734
2735 /* Set up LP accel mode. */
2736 data[0] = BIT_LPA_CYCLE;
2737 if (lpa_freq == 1)
2738 data[1] = INV_LPA_1_25HZ;
2739 else if (lpa_freq <= 5)
2740 data[1] = INV_LPA_5HZ;
2741 else if (lpa_freq <= 20)
2742 data[1] = INV_LPA_20HZ;
2743 else
2744 data[1] = INV_LPA_40HZ;
2745 data[1] = (data[1] << 6) | BIT_STBY_XYZG;
2746 if (i2c_write(st.hw->addr, st.reg->pwr_mgmt_1, 2, data))
2747 goto lp_int_restore;
2748
2750 return 0;
2751#elif defined MPU6500
2752 /* Disable hardware interrupts. */
2753 set_int_enable(0);
2754
2755 /* Enter full-power accel-only mode, no FIFO/DMP. */
2756 data[0] = 0;
2757 data[1] = 0;
2758 data[2] = BIT_STBY_XYZG;
2759 if (i2c_write(st.hw->addr, st.reg->user_ctrl, 3, data))
2760 goto lp_int_restore;
2761
2762 /* Set motion threshold. */
2763 data[0] = thresh_hw;
2764 if (i2c_write(st.hw->addr, st.reg->motion_thr, 1, data))
2765 goto lp_int_restore;
2766
2767 /* Set wake frequency. */
2768 if (lpa_freq == 1)
2769 data[0] = INV_LPA_1_25HZ;
2770 else if (lpa_freq == 2)
2771 data[0] = INV_LPA_2_5HZ;
2772 else if (lpa_freq <= 5)
2773 data[0] = INV_LPA_5HZ;
2774 else if (lpa_freq <= 10)
2775 data[0] = INV_LPA_10HZ;
2776 else if (lpa_freq <= 20)
2777 data[0] = INV_LPA_20HZ;
2778 else if (lpa_freq <= 40)
2779 data[0] = INV_LPA_40HZ;
2780 else if (lpa_freq <= 80)
2781 data[0] = INV_LPA_80HZ;
2782 else if (lpa_freq <= 160)
2783 data[0] = INV_LPA_160HZ;
2784 else if (lpa_freq <= 320)
2785 data[0] = INV_LPA_320HZ;
2786 else
2787 data[0] = INV_LPA_640HZ;
2788 if (i2c_write(st.hw->addr, st.reg->lp_accel_odr, 1, data))
2789 goto lp_int_restore;
2790
2791 /* Enable motion interrupt (MPU6500 version). */
2792 data[0] = BITS_WOM_EN;
2793 if (i2c_write(st.hw->addr, st.reg->accel_intel, 1, data))
2794 goto lp_int_restore;
2795
2796 /* Enable cycle mode. */
2797 data[0] = BIT_LPA_CYCLE;
2798 if (i2c_write(st.hw->addr, st.reg->pwr_mgmt_1, 1, data))
2799 goto lp_int_restore;
2800
2801 /* Enable interrupt. */
2802 data[0] = BIT_MOT_INT_EN;
2803 if (i2c_write(st.hw->addr, st.reg->int_enable, 1, data))
2804 goto lp_int_restore;
2805
2807 return 0;
2808#endif
2809 } else {
2810 /* Don't "restore" the previous state if no state has been saved. */
2811 int ii;
2812 char *cache_ptr = (char*)&st.chip_cfg.cache;
2813 for (ii = 0; ii < sizeof(st.chip_cfg.cache); ii++) {
2814 if (cache_ptr[ii] != 0)
2815 goto lp_int_restore;
2816 }
2817 /* If we reach this point, motion interrupt mode hasn't been used yet. */
2818 return -1;
2819 }
2820lp_int_restore:
2821 /* Set to invalid values to ensure no I2C writes are skipped. */
2822 st.chip_cfg.gyro_fsr = 0xFF;
2823 st.chip_cfg.accel_fsr = 0xFF;
2824 st.chip_cfg.lpf = 0xFF;
2825 st.chip_cfg.sample_rate = 0xFFFF;
2826 st.chip_cfg.sensors = 0xFF;
2827 st.chip_cfg.fifo_enable = 0xFF;
2835
2836 if (st.chip_cfg.cache.dmp_on)
2838
2839#ifdef MPU6500
2840 /* Disable motion interrupt (MPU6500 version). */
2841 data[0] = 0;
2842 if (i2c_write(st.hw->addr, st.reg->accel_intel, 1, data))
2843 goto lp_int_restore;
2844#endif
2845
2847 return 0;
2848}
2850//添加的代码部分
2852//本程序只供学习使用,未经作者许可,不得用于其它任何用途
2853//ALIENTEK精英STM32开发板V3
2854//MPU6050 DMP 驱动代码
2855//正点原子@ALIENTEK
2856//技术论坛:www.openedv.com
2857//创建日期:2015/1/17
2858//版本:V1.0
2859//版权所有,盗版必究。
2860//Copyright(C) 广州市星翼电子科技有限公司 2009-2019
2861//All rights reserved
2863
2864//q30格式,long转float时的除数.
2865#define q30 1073741824.0f
2866
2867//陀螺仪方向设置
2868static signed char gyro_orientation[9] = { 1, 0, 0,
2869 0, 1, 0,
2870 0, 0, 1};
2871//MPU6050自测试
2872//返回值:0,正常
2873// 其他,失败
2875 int result;
2876 //char test_packet[4] = {0};
2877 long gyro[3], accel[3];
2878 result = mpu_run_self_test(gyro, accel);
2879 if (result == 0x3){
2880 /* Test passed. We can trust the gyro data here, so let's push it down
2881 * to the DMP.
2882 */
2883 float sens;
2884 unsigned short accel_sens;
2885 mpu_get_gyro_sens(&sens);
2886 gyro[0] = (long)(gyro[0] * sens);
2887 gyro[1] = (long)(gyro[1] * sens);
2888 gyro[2] = (long)(gyro[2] * sens);
2889 dmp_set_gyro_bias(gyro);
2890 mpu_get_accel_sens(&accel_sens);
2891 accel[0] *= accel_sens;
2892 accel[1] *= accel_sens;
2893 accel[2] *= accel_sens;
2894 dmp_set_accel_bias(accel);
2895 return 0;
2896 }else return 1;}
2897//陀螺仪方向控制
2899 const signed char *mtx){
2900 unsigned short scalar;
2901 /*
2902 XYZ 010_001_000 Identity Matrix
2903 XZY 001_010_000
2904 YXZ 010_000_001
2905 YZX 000_010_001
2906 ZXY 001_000_010
2907 ZYX 000_001_010
2908 */
2909 scalar = inv_row_2_scale(mtx);
2910 scalar |= inv_row_2_scale(mtx + 3) << 3;
2911 scalar |= inv_row_2_scale(mtx + 6) << 6;
2912 return scalar;}
2913//方向转换
2914unsigned short inv_row_2_scale(const signed char *row){
2915 unsigned short b;
2916
2917 if (row[0] > 0)
2918 b = 0;
2919 else if (row[0] < 0)
2920 b = 4;
2921 else if (row[1] > 0)
2922 b = 1;
2923 else if (row[1] < 0)
2924 b = 5;
2925 else if (row[2] > 0)
2926 b = 2;
2927 else if (row[2] < 0)
2928 b = 6;
2929 else
2930 b = 7; // error
2931 return b;}
2932//空函数,未用到.
2933void mget_ms(unsigned long *time){}
2934//mpu6050,dmp初始化
2935//返回值:0,正常
2936// 其他,失败
2938{
2939 u8 res=0;
2940 if(mpu_init()==0) //初始化MPU6050
2941 {
2942 res=mpu_set_sensors(INV_XYZ_GYRO|INV_XYZ_ACCEL); //设置所需要的传感器
2943 if(res)return 1;
2945 if(res)return 2;
2946 res=mpu_set_sample_rate(DEFAULT_MPU_HZ); //设置采样率
2947 if(res)return 3;
2948 res=dmp_load_motion_driver_firmware(); //加载dmp固件
2949 if(res)return 4;
2951 if(res)return 5;
2955 if(res)return 6;
2956 res=dmp_set_fifo_rate(DEFAULT_MPU_HZ); //设置DMP输出速率(最大不超过200Hz)
2957 if(res)return 7;
2958 res=run_self_test(); //自检
2959 if(res)return 8;
2960 res=mpu_set_dmp_state(1); //使能DMP
2961 if(res)return 9;
2962 }else return 10;
2963 return 0;}
2964//得到dmp处理后的数据(注意,本函数需要比较多堆栈,局部变量有点多)
2965//pitch:俯仰角 精度:0.1° 范围:-90.0° <---> +90.0°
2966//roll:横滚角 精度:0.1° 范围:-180.0°<---> +180.0°
2967//yaw:航向角 精度:0.1° 范围:-180.0°<---> +180.0°
2968//返回值:0,正常
2969// 其他,失败
2970u8 mpu_dmp_get_data(float *pitch,float *roll,float *yaw){
2971 float q0=1.0f,q1=0.0f,q2=0.0f,q3=0.0f;
2972 unsigned long sensor_timestamp;
2973 short gyro[3], accel[3], sensors;
2974 unsigned char more;
2975 long quat[4];
2976 if(dmp_read_fifo(gyro, accel, quat, &sensor_timestamp, &sensors,&more))return 1;
2977 /* Gyro and accel data are written to the FIFO by the DMP in chip frame and hardware units.
2978 * This behavior is convenient because it keeps the gyro and accel outputs of dmp_read_fifo and mpu_read_fifo consistent.
2979 **/
2980 /*if (sensors & INV_XYZ_GYRO )
2981 send_packet(PACKET_TYPE_GYRO, gyro);
2982 if (sensors & INV_XYZ_ACCEL)
2983 send_packet(PACKET_TYPE_ACCEL, accel); */
2984 /* Unlike gyro and accel, quaternions are written to the FIFO in the body frame, q30.
2985 * The orientation is set by the scalar passed to dmp_set_orientation during initialization.
2986 **/
2987 if(sensors&INV_WXYZ_QUAT)
2988 {
2989 q0 = quat[0] / q30; //q30格式转换为浮点数
2990 q1 = quat[1] / q30;
2991 q2 = quat[2] / q30;
2992 q3 = quat[3] / q30;
2993 //计算得到俯仰角/横滚角/航向角
2994 *pitch = asin(-2 * q1 * q3 + 2 * q0* q2)* 57.3; // pitch
2995 *roll = atan2(2 * q2 * q3 + 2 * q0 * q1, -2 * q1 * q1 - 2 * q2* q2 + 1)* 57.3; // roll
2996 *yaw = atan2(2*(q1*q2 + q0*q3),q0*q0+q1*q1-q2*q2-q3*q3) * 57.3; //yaw
2997 }else return 2;
2998 return 0;
2999}
int mpu_set_sample_rate(unsigned short rate)
Set sampling rate. Sampling rate must be between 4Hz and 1kHz.
Definition: inv_mpu.c:1367
int mpu_get_gyro_sens(float *sens)
Get gyro sensitivity scale factor.
Definition: inv_mpu.c:1458
#define BIT_DMP_EN
Definition: inv_mpu.c:369
int dmp_read_fifo(short *gyro, short *accel, long *quat, unsigned long *timestamp, short *sensors, unsigned char *more)
Get one packet from the FIFO. If sensors does not contain a particular sensor, disregard the data ret...
#define BIT_STBY_XYZA
Definition: inv_mpu.c:406
int mpu_get_fifo_config(unsigned char *sensors)
Get current FIFO configuration. sensors can contain a combination of the following flags: INV_X_GYR...
Definition: inv_mpu.c:1516
unsigned char reg_lpf
Definition: inv_mpu.c:285
int mpu_get_int_status(short *status)
Read the MPU interrupt status registers.
Definition: inv_mpu.c:1669
#define q30
Definition: inv_mpu.c:2865
int mpu_reg_dump(void)
Register dump for testing.
Definition: inv_mpu.c:713
unsigned char num_reg
Definition: inv_mpu.c:208
unsigned char user_ctrl
Definition: inv_mpu.c:161
int mpu_read_fifo_stream(unsigned short length, unsigned char *data, unsigned char *more)
Get one unparsed packet from the FIFO. This function should be used if the packet is to be parsed els...
Definition: inv_mpu.c:1779
unsigned char lpf
Definition: inv_mpu.c:242
unsigned short sample_rate
Definition: inv_mpu.c:225
unsigned char dmp_loaded
Definition: inv_mpu.c:269
const struct test_s test
Definition: inv_mpu.c:555
#define BIT_ANY_RD_CLR
Definition: inv_mpu.c:396
#define BIT_SLEEP
Definition: inv_mpu.c:384
unsigned char lpf
Definition: inv_mpu.c:159
lp_accel_rate_e
Definition: inv_mpu.c:345
int mpu_get_sample_rate(unsigned short *rate)
Get sampling rate.
Definition: inv_mpu.c:1352
unsigned short sample_rate
Definition: inv_mpu.c:245
static int gyro_self_test(long *bias_regular, long *bias_st)
Definition: inv_mpu.c:1945
int mpu_set_accel_fsr(unsigned char fsr)
Set the accel full-scale range.
Definition: inv_mpu.c:1246
unsigned char int_motion_only
Definition: inv_mpu.c:260
unsigned char rate_div
Definition: inv_mpu.c:158
#define log_i
Definition: inv_mpu.c:57
#define DEFAULT_MPU_HZ
Definition: inv_mpu.h:27
unsigned short inv_row_2_scale(const signed char *row)
Definition: inv_mpu.c:2914
unsigned char i2c_mst
Definition: inv_mpu.c:183
int mpu_read_fifo(short *gyro, short *accel, unsigned long *timestamp, unsigned char *sensors, unsigned char *more)
Get one packet from the FIFO. If sensors does not contain a particular sensor, disregard the data ret...
Definition: inv_mpu.c:1698
#define BIT_STBY_ZG
Definition: inv_mpu.c:405
unsigned long gyro_sens
Definition: inv_mpu.c:282
int mpu_read_mem(unsigned short mem_addr, unsigned short length, unsigned char *data)
Read from the DMP memory. This function prevents I2C reads past the bank boundaries....
Definition: inv_mpu.c:2304
unsigned char lp_accel_mode
Definition: inv_mpu.c:258
int mpu_set_bypass(unsigned char bypass_on)
Set device to bypass mode.
Definition: inv_mpu.c:1817
#define BIT_FIFO_SIZE_1024
Definition: inv_mpu.c:380
int mpu_run_self_test(long *gyro, long *accel)
Trigger gyro/accel/compass self-test. On success/error, the self-test returns a mask representing the...
Definition: inv_mpu.c:2169
#define BIT_DMP_RST
Definition: inv_mpu.c:371
static struct gyro_state_s st
Definition: inv_mpu.c:577
int mpu_lp_accel_mode(unsigned char rate)
Enter low-power accel-only mode. In low-power accel mode, the chip goes to sleep and only wakes up to...
Definition: inv_mpu.c:888
float max_gyro_var
Definition: inv_mpu.c:292
unsigned char reg_accel_fsr
Definition: inv_mpu.c:287
unsigned char reg_rate_div
Definition: inv_mpu.c:284
#define BITS_HPF
Definition: inv_mpu.c:378
#define INV_WXYZ_QUAT
unsigned char pwr_mgmt_2
Definition: inv_mpu.c:179
#define get_ms
Definition: inv_mpu.c:50
#define INV_XYZ_GYRO
Definition: inv_mpu.h:32
unsigned short inv_orientation_matrix_to_scalar(const signed char *mtx)
Definition: inv_mpu.c:2898
#define DMP_FEATURE_SEND_CAL_GYRO
unsigned char fifo_sensors
Definition: inv_mpu.c:227
const struct gyro_reg_s * reg
Definition: inv_mpu.c:300
#define BIT_DATA_RDY_EN
Definition: inv_mpu.c:373
unsigned char lp_exit
Definition: inv_mpu.h:41
int setup_compass(void)
Definition: inv_mpu.c:2424
int dmp_set_gyro_bias(long *bias)
Push gyro biases to the DMP. Because the gyro integration is handled in the DMP, any gyro biases calc...
unsigned char temp
Definition: inv_mpu.c:173
unsigned char dmp_on
Definition: inv_mpu.c:267
unsigned char int_enable
Definition: inv_mpu.c:174
int mpu_set_accel_bias(const long *accel_bias)
Push biases to the accel bias registers. This function expects biases relative to the current sensor ...
Definition: inv_mpu.c:1043
#define BIT_DMP_INT_EN
Definition: inv_mpu.c:374
#define BIT_STBY_XYZG
Definition: inv_mpu.c:407
#define INV_Z_GYRO
Definition: inv_mpu.h:31
unsigned char who_am_i
Definition: inv_mpu.c:157
int dmp_set_fifo_rate(unsigned short rate)
Set DMP output rate. Only used when DMP is on.
const struct gyro_reg_s reg
Definition: inv_mpu.c:489
int mpu_get_gyro_reg(short *data, unsigned long *timestamp)
Read raw gyro data directly from the registers.
Definition: inv_mpu.c:972
unsigned char latched_int
Definition: inv_mpu.c:265
int mpu_set_lpf(unsigned short lpf)
Set digital low pass filter. The following LPF settings are supported: 188, 98, 42,...
Definition: inv_mpu.c:1319
short temp_offset
Definition: inv_mpu.c:210
unsigned char motion_dur
Definition: inv_mpu.c:168
#define BIT_LATCH_EN
Definition: inv_mpu.c:395
const struct test_s * test
Definition: inv_mpu.c:303
int mpu_read_reg(unsigned char reg, unsigned char *data)
Read from a single register. NOTE: The memory and FIFO read/write registers cannot be accessed.
Definition: inv_mpu.c:735
unsigned short pin
Definition: inv_mpu.h:40
unsigned short dmp_sample_rate
Definition: inv_mpu.c:271
unsigned long accel_sens
Definition: inv_mpu.c:283
unsigned short max_fifo
Definition: inv_mpu.c:207
int mpu_get_accel_sens(unsigned short *sens)
Get accel sensitivity scale factor.
Definition: inv_mpu.c:1484
#define BIT_LPA_CYCLE
Definition: inv_mpu.c:399
unsigned char dmp_on
Definition: inv_mpu.c:228
int mpu_set_int_latched(unsigned char enable)
Enable latched interrupts. Any MPU register will clear the interrupt.
Definition: inv_mpu.c:1879
int mpu_get_compass_reg(short *data, unsigned long *timestamp)
Read raw compass data.
Definition: inv_mpu.c:2535
int dmp_load_motion_driver_firmware(void)
Load the DMP with this image.
int mpu_set_dmp_state(unsigned char enable)
Enable/disable DMP support.
Definition: inv_mpu.c:2377
void log_none(char *fmt,...)
Definition: inv_mpu.c:56
unsigned char fifo_en
Definition: inv_mpu.c:162
#define BIT_MOT_INT_EN
Definition: inv_mpu.c:375
int dmp_set_orientation(unsigned short orient)
Push gyro and accel orientation to the DMP. The orientation is represented here as the output of inv_...
unsigned char bypass_mode
Definition: inv_mpu.c:251
int mpu_set_sensors(unsigned char sensors)
Turn specific sensors on/off. sensors can contain a combination of the following flags: INV_X_GYRO,...
Definition: inv_mpu.c:1592
unsigned char active_low_int
Definition: inv_mpu.c:263
int dmp_enable_feature(unsigned short mask)
Enable DMP features. The following #define's are used in the input mask: DMP_FEATURE_TAP DMP_FEAT...
clock_sel_e
Definition: inv_mpu.c:338
#define BITS_WOM_EN
Definition: inv_mpu.c:398
int mpu_set_compass_sample_rate(unsigned short rate)
Set compass sampling rate. The compass on the auxiliary I2C bus is read by the MPU hardware at a maxi...
Definition: inv_mpu.c:1436
unsigned char mem_start_addr
Definition: inv_mpu.c:185
int mpu_lp_motion_interrupt(unsigned short thresh, unsigned char time, unsigned char lpa_freq)
Enters LP accel motion interrupt mode. The behavior of this feature is very different between the MPU...
Definition: inv_mpu.c:2642
float max_accel_var
Definition: inv_mpu.c:295
#define INV_XYZ_COMPASS
Definition: inv_mpu.h:34
const struct hw_s hw
Definition: inv_mpu.c:530
#define BIT_STBY_XG
Definition: inv_mpu.c:403
unsigned char int_status
Definition: inv_mpu.c:176
#define i2c_read
Definition: inv_mpu.c:48
gyro_fsr_e
Definition: inv_mpu.c:320
#define BIT_ACTL
Definition: inv_mpu.c:394
#define DMP_FEATURE_TAP
unsigned char fifo_enable
Definition: inv_mpu.c:247
struct chip_cfg_s chip_cfg
Definition: inv_mpu.c:302
unsigned char packet_thresh
Definition: inv_mpu.c:289
static int get_st_biases(long *gyro, long *accel, unsigned char hw_test)
Definition: inv_mpu.c:2029
#define BIT_I2C_READ
Definition: inv_mpu.c:391
int mpu_load_firmware(unsigned short length, const unsigned char *firmware, unsigned short start_addr, unsigned short sample_rate)
Load and verify DMP image.
Definition: inv_mpu.c:2336
lpf_e
Definition: inv_mpu.c:307
#define fabs
Definition: inv_mpu.c:61
void(* cb)(void)
Definition: inv_mpu.h:39
#define MAX_PACKET_LENGTH
Definition: inv_mpu.c:667
unsigned char raw_accel
Definition: inv_mpu.c:172
unsigned char active_low
Definition: inv_mpu.h:42
float max_g
Definition: inv_mpu.c:294
#define DMP_FEATURE_SEND_RAW_ACCEL
unsigned char pwr_mgmt_1
Definition: inv_mpu.c:178
#define INV_XYZ_ACCEL
Definition: inv_mpu.h:33
unsigned char reg_gyro_fsr
Definition: inv_mpu.c:286
#define i2c_write
Definition: inv_mpu.c:47
unsigned char int_enable
Definition: inv_mpu.c:249
int mpu_get_temperature(long *data, unsigned long *timestamp)
Read temperature data directly from the registers.
Definition: inv_mpu.c:1018
int mpu_get_lpf(unsigned short *lpf)
Get the current DLPF setting.
Definition: inv_mpu.c:1283
unsigned char sensors
Definition: inv_mpu.c:240
static int accel_self_test(long *bias_regular, long *bias_st)
Definition: inv_mpu.c:1925
unsigned char prgm_start_h
Definition: inv_mpu.c:186
unsigned char int_pin_cfg
Definition: inv_mpu.c:180
#define DMP_FEATURE_GYRO_CAL
unsigned char motion_thr
Definition: inv_mpu.c:167
unsigned short temp_sens
Definition: inv_mpu.c:209
#define log_e
Definition: inv_mpu.c:58
unsigned char gyro_fsr
Definition: inv_mpu.c:236
int mpu_get_compass_sample_rate(unsigned short *rate)
Get compass sampling rate.
Definition: inv_mpu.c:1414
unsigned char raw_gyro
Definition: inv_mpu.c:171
int mpu_get_accel_fsr(unsigned char *fsr)
Get the accel full-scale range.
Definition: inv_mpu.c:1218
unsigned char accel_half
Definition: inv_mpu.c:256
unsigned char accel_offs
Definition: inv_mpu.c:182
unsigned char fifo_count_h
Definition: inv_mpu.c:169
unsigned char clk_src
Definition: inv_mpu.c:243
static int get_accel_prod_shift(float *st_shift)
Definition: inv_mpu.c:1900
int mpu_configure_fifo(unsigned char sensors)
Select which sensors are pushed to FIFO. sensors can contain a combination of the following flags: ...
Definition: inv_mpu.c:1531
#define BIT_AUX_IF_EN
Definition: inv_mpu.c:393
#define INV_X_GYRO
Definition: inv_mpu.h:29
#define BIT_STBY_YG
Definition: inv_mpu.c:404
unsigned short lpf
Definition: inv_mpu.c:224
const struct hw_s * hw
Definition: inv_mpu.c:301
int mpu_init(void)
Initialize hardware. Initial configuration: Gyro FSR: +/- 2000DPS Accel FSR +/- 2G DLPF: 42Hz FIFO ra...
Definition: inv_mpu.c:757
#define BIT_I2C_MST_VDDIO
Definition: inv_mpu.c:367
#define min(a, b)
Definition: inv_mpu.c:62
unsigned char addr
Definition: inv_mpu.c:206
unsigned char fifo_r_w
Definition: inv_mpu.c:170
u8 mpu_dmp_get_data(float *pitch, float *roll, float *yaw)
Definition: inv_mpu.c:2970
int mpu_set_int_level(unsigned char active_low)
Set interrupt level.
Definition: inv_mpu.c:1867
#define INV_Y_GYRO
Definition: inv_mpu.h:30
unsigned char accel_fsr
Definition: inv_mpu.c:223
int mpu_set_gyro_fsr(unsigned short fsr)
Set the gyro full-scale range.
Definition: inv_mpu.c:1181
unsigned char gyro_cfg
Definition: inv_mpu.c:163
static signed char gyro_orientation[9]
Definition: inv_mpu.c:2868
#define BIT_BYPASS_EN
Definition: inv_mpu.c:397
int mpu_get_compass_fsr(unsigned short *fsr)
Get the compass full-scale range.
Definition: inv_mpu.c:2588
struct motion_int_cache_s cache
Definition: inv_mpu.c:261
unsigned char mem_r_w
Definition: inv_mpu.c:181
#define delay_ms
Definition: inv_mpu.c:49
#define BIT_FIFO_EN
Definition: inv_mpu.c:368
int mpu_get_accel_reg(short *data, unsigned long *timestamp)
Read raw accel data directly from the registers.
Definition: inv_mpu.c:995
unsigned char sensors_on
Definition: inv_mpu.c:226
float max_dps
Definition: inv_mpu.c:291
float min_g
Definition: inv_mpu.c:293
#define DMP_FEATURE_6X_LP_QUAT
unsigned char accel_cfg
Definition: inv_mpu.c:164
#define BIT_SLAVE_EN
Definition: inv_mpu.c:390
unsigned short gyro_fsr
Definition: inv_mpu.c:222
unsigned char dmp_int_status
Definition: inv_mpu.c:175
#define BIT_FIFO_RST
Definition: inv_mpu.c:370
accel_fsr_e
Definition: inv_mpu.c:329
int mpu_get_power_state(unsigned char *power_on)
Get current power state.
Definition: inv_mpu.c:1573
unsigned short bank_size
Definition: inv_mpu.c:211
unsigned char bank_sel
Definition: inv_mpu.c:184
int mpu_reset_fifo(void)
Reset FIFO read/write pointers.
Definition: inv_mpu.c:1092
#define DMP_FEATURE_ANDROID_ORIENT
unsigned char prod_id
Definition: inv_mpu.c:160
#define BIT_RESET
Definition: inv_mpu.c:383
unsigned short wait_ms
Definition: inv_mpu.c:288
unsigned char accel_fsr
Definition: inv_mpu.c:238
int mpu_get_gyro_fsr(unsigned short *fsr)
Get the gyro full-scale range.
Definition: inv_mpu.c:1154
void mget_ms(unsigned long *time)
Definition: inv_mpu.c:2933
u8 mpu_dmp_init(void)
Definition: inv_mpu.c:2937
float min_dps
Definition: inv_mpu.c:290
#define BIT_FIFO_OVERFLOW
Definition: inv_mpu.c:372
int dmp_set_accel_bias(long *bias)
Push accel biases to the DMP. These biases will be removed from the DMP 6-axis quaternion.
static int set_int_enable(unsigned char enable)
Enable/disable data ready interrupt. If the DMP is on, the DMP interrupt is enabled....
Definition: inv_mpu.c:681
int mpu_get_dmp_state(unsigned char *enabled)
Get DMP state.
Definition: inv_mpu.c:2416
int mpu_write_mem(unsigned short mem_addr, unsigned short length, unsigned char *data)
Write to the DMP memory. This function prevents I2C writes past the bank boundaries....
Definition: inv_mpu.c:2271
u8 run_self_test(void)
Definition: inv_mpu.c:2874
@ INV_LPA_5HZ
Definition: inv_mpu.c:348
@ INV_LPA_40HZ
Definition: inv_mpu.c:350
@ INV_LPA_1_25HZ
Definition: inv_mpu.c:347
@ INV_LPA_20HZ
Definition: inv_mpu.c:349
@ INV_CLK_PLL
Definition: inv_mpu.c:340
@ NUM_CLK
Definition: inv_mpu.c:341
@ INV_CLK_INTERNAL
Definition: inv_mpu.c:339
@ INV_FSR_500DPS
Definition: inv_mpu.c:322
@ INV_FSR_250DPS
Definition: inv_mpu.c:321
@ NUM_GYRO_FSR
Definition: inv_mpu.c:325
@ INV_FSR_2000DPS
Definition: inv_mpu.c:324
@ INV_FSR_1000DPS
Definition: inv_mpu.c:323
@ NUM_FILTER
Definition: inv_mpu.c:316
@ INV_FILTER_98HZ
Definition: inv_mpu.c:310
@ INV_FILTER_10HZ
Definition: inv_mpu.c:313
@ INV_FILTER_2100HZ_NOLPF
Definition: inv_mpu.c:315
@ INV_FILTER_42HZ
Definition: inv_mpu.c:311
@ INV_FILTER_256HZ_NOLPF2
Definition: inv_mpu.c:308
@ INV_FILTER_188HZ
Definition: inv_mpu.c:309
@ INV_FILTER_5HZ
Definition: inv_mpu.c:314
@ INV_FILTER_20HZ
Definition: inv_mpu.c:312
@ INV_FSR_8G
Definition: inv_mpu.c:332
@ INV_FSR_16G
Definition: inv_mpu.c:333
@ NUM_ACCEL_FSR
Definition: inv_mpu.c:334
@ INV_FSR_4G
Definition: inv_mpu.c:331
@ INV_FSR_2G
Definition: inv_mpu.c:330
#define LOAD_CHUNK
An I2C-based driver for Invensense gyroscopes.
DMP image and interface functions.
Definition: inv_mpu.c:205
uint8_t u8
8位无符号数类型
Definition: varint.h:40