明石高専ロボ研 mbedライブラリ

Dependencies:   mbed

Dependents:   MDD_L432KC USB2RS485 pathtracking odometry ... more

Committer:
TanakaRobo
Date:
Wed Oct 13 09:12:48 2021 +0000
Revision:
14:bdd394483434
Parent:
4:39ef4d91dc34
first? commit

Who changed what in which revision?

UserRevisionLine numberNew contents of line
TanakaRobo 0:ca84ed7518f5 1 #include "gy521.hpp"
TanakaRobo 0:ca84ed7518f5 2
TanakaRobo 0:ca84ed7518f5 3 const double GY521_LSB_MAP[4] = {131, 65.5, 32.8, 16.4};
TanakaRobo 0:ca84ed7518f5 4 const unsigned int dev_id = 0x68 << 1;
TanakaRobo 0:ca84ed7518f5 5
TanakaRobo 0:ca84ed7518f5 6 GY521::GY521(I2C &i2c,int bit,int calibration,double user_reg):i2c_(i2c),bit_(bit),calibration_(calibration){
TanakaRobo 0:ca84ed7518f5 7 char check;
TanakaRobo 0:ca84ed7518f5 8 char data[2] = {WHO_AM_I,0x00};
TanakaRobo 0:ca84ed7518f5 9 i2c_.write(dev_id,data,1,true);
TanakaRobo 0:ca84ed7518f5 10 i2c_.read(dev_id,&check,1);
TanakaRobo 0:ca84ed7518f5 11 if(check == dev_id >> 1){
TanakaRobo 0:ca84ed7518f5 12 data[0] = PWR_MGMT_1;
TanakaRobo 0:ca84ed7518f5 13 i2c_.write(dev_id,data,1,true);
TanakaRobo 0:ca84ed7518f5 14 i2c_.read(dev_id,&check,1);
TanakaRobo 0:ca84ed7518f5 15 if(check == 0x40){
TanakaRobo 0:ca84ed7518f5 16 i2c_.write(dev_id,data,2);
TanakaRobo 0:ca84ed7518f5 17 }
TanakaRobo 0:ca84ed7518f5 18 }
TanakaRobo 0:ca84ed7518f5 19 data[0] = LPF;
TanakaRobo 0:ca84ed7518f5 20 data[1] = 0x00;
TanakaRobo 0:ca84ed7518f5 21 i2c_.write(dev_id,data,2);
TanakaRobo 0:ca84ed7518f5 22 data[0] = AFS_SEL;
TanakaRobo 0:ca84ed7518f5 23 data[1] = 0x00;
TanakaRobo 0:ca84ed7518f5 24 i2c_.write(dev_id,data,2);
TanakaRobo 0:ca84ed7518f5 25 short accel_x_now = 0,accel_y_now = 0,accel_z_now = 0;
TanakaRobo 0:ca84ed7518f5 26 double accel_x_aver = 0, accel_y_aver = 0, accel_z_aver = 0;
TanakaRobo 0:ca84ed7518f5 27 for (int i = 0; i < calibration_; ++i) {
TanakaRobo 0:ca84ed7518f5 28 accel_x_now = gyroRead2(ACCEL_XOUT_H);
TanakaRobo 0:ca84ed7518f5 29 accel_y_now = gyroRead2(ACCEL_YOUT_H);
TanakaRobo 0:ca84ed7518f5 30 accel_z_now = gyroRead2(ACCEL_ZOUT_H);
TanakaRobo 0:ca84ed7518f5 31 accel_x_aver += accel_x_now;
TanakaRobo 0:ca84ed7518f5 32 accel_y_aver += accel_y_now;
TanakaRobo 0:ca84ed7518f5 33 accel_z_aver += accel_z_now;
TanakaRobo 0:ca84ed7518f5 34 }
TanakaRobo 0:ca84ed7518f5 35 accel_x_aver /= calibration_;
TanakaRobo 0:ca84ed7518f5 36 accel_y_aver /= calibration_;
TanakaRobo 0:ca84ed7518f5 37 accel_z_aver /= calibration_;
TanakaRobo 0:ca84ed7518f5 38 double gyro_reg = hypot(hypot(accel_x_aver, accel_y_aver), accel_z_aver) / accel_z_aver;
TanakaRobo 0:ca84ed7518f5 39 data[0] = FS_SEL;
TanakaRobo 0:ca84ed7518f5 40 data[1] = bit << 3;
TanakaRobo 0:ca84ed7518f5 41 i2c_.write(dev_id,data,2);
TanakaRobo 0:ca84ed7518f5 42 gyro_LSB_ = GY521_LSB_MAP[bit_] / gyro_reg / user_reg;
TanakaRobo 0:ca84ed7518f5 43
TanakaRobo 0:ca84ed7518f5 44 short gyro_z_now_;
TanakaRobo 0:ca84ed7518f5 45 gyro_z_aver_ = 0;
TanakaRobo 0:ca84ed7518f5 46 for (int i = 0; i < calibration_; ++i) {
TanakaRobo 0:ca84ed7518f5 47 gyro_z_now_ = gyroRead2(GYRO_ZOUT_H);
TanakaRobo 0:ca84ed7518f5 48 gyro_z_aver_ += gyro_z_now_;
TanakaRobo 0:ca84ed7518f5 49 }
TanakaRobo 0:ca84ed7518f5 50 gyro_z_aver_ /= calibration_;
TanakaRobo 0:ca84ed7518f5 51
TanakaRobo 0:ca84ed7518f5 52 yaw = diff_yaw_ = 0;
TanakaRobo 0:ca84ed7518f5 53 timer_.start();
TanakaRobo 0:ca84ed7518f5 54 flag_ = false;
TanakaRobo 0:ca84ed7518f5 55 }
TanakaRobo 0:ca84ed7518f5 56
TanakaRobo 3:28c77df7c0b6 57 void GY521::update(){
TanakaRobo 0:ca84ed7518f5 58 if(flag_){
TanakaRobo 0:ca84ed7518f5 59 return;
TanakaRobo 0:ca84ed7518f5 60 }
TanakaRobo 0:ca84ed7518f5 61 short gyro_z_now_ = gyroRead2(GYRO_ZOUT_H);
TanakaRobo 0:ca84ed7518f5 62 gyro_z_now_ = ((double)gyro_z_now_ - gyro_z_aver_) / gyro_LSB_;
TanakaRobo 0:ca84ed7518f5 63 diff_yaw_ = (gyro_z_now_ + gyro_z_prev_) / 2 * timer_.read();
TanakaRobo 0:ca84ed7518f5 64 timer_.reset();
TanakaRobo 0:ca84ed7518f5 65 yaw += diff_yaw_;
TanakaRobo 0:ca84ed7518f5 66 gyro_z_prev_ = gyro_z_now_;
TanakaRobo 0:ca84ed7518f5 67 //temp = (double)gyroRead2(TEMPERATURE)/340+36.53;
TanakaRobo 0:ca84ed7518f5 68 if (yaw > 180) {
TanakaRobo 0:ca84ed7518f5 69 yaw -= 360;
TanakaRobo 0:ca84ed7518f5 70 } else if (yaw <= -180) {
TanakaRobo 0:ca84ed7518f5 71 yaw += 360;
TanakaRobo 0:ca84ed7518f5 72 }
TanakaRobo 0:ca84ed7518f5 73 }
TanakaRobo 0:ca84ed7518f5 74
TanakaRobo 0:ca84ed7518f5 75 void GY521::reset(int user){
TanakaRobo 0:ca84ed7518f5 76 yaw = user;
TanakaRobo 0:ca84ed7518f5 77 short gyro_z_now_;
TanakaRobo 0:ca84ed7518f5 78 flag_ = true;
TanakaRobo 0:ca84ed7518f5 79 gyro_z_aver_ = 0;
TanakaRobo 0:ca84ed7518f5 80 for (int i = 0; i < calibration_; i++) {
TanakaRobo 0:ca84ed7518f5 81 gyro_z_now_ = gyroRead2(GYRO_ZOUT_H);
TanakaRobo 0:ca84ed7518f5 82 gyro_z_aver_ += gyro_z_now_;
TanakaRobo 0:ca84ed7518f5 83 }
TanakaRobo 0:ca84ed7518f5 84 gyro_z_aver_ /= calibration_;
TanakaRobo 0:ca84ed7518f5 85 flag_ = false;
TanakaRobo 0:ca84ed7518f5 86 }
TanakaRobo 0:ca84ed7518f5 87
TanakaRobo 0:ca84ed7518f5 88 double GY521::checkStatus(int mode) {
TanakaRobo 0:ca84ed7518f5 89 if (mode == 0) {
TanakaRobo 0:ca84ed7518f5 90 return gyro_LSB_;
TanakaRobo 0:ca84ed7518f5 91 } else if (mode == 1) {
TanakaRobo 0:ca84ed7518f5 92 return gyro_z_aver_;
TanakaRobo 0:ca84ed7518f5 93 } else if (mode == 2) {
TanakaRobo 0:ca84ed7518f5 94 return acos(gyro_LSB_ / GY521_LSB_MAP[bit_]);
TanakaRobo 0:ca84ed7518f5 95 }
TanakaRobo 0:ca84ed7518f5 96 return 0;
TanakaRobo 0:ca84ed7518f5 97 }
TanakaRobo 0:ca84ed7518f5 98
TanakaRobo 0:ca84ed7518f5 99 int16_t GY521::gyroRead2(enum GY521RegisterMap reg) {
TanakaRobo 0:ca84ed7518f5 100 char data[2];
TanakaRobo 0:ca84ed7518f5 101 char addr = reg;
TanakaRobo 0:ca84ed7518f5 102 i2c_.write(dev_id,&addr,1,true);
TanakaRobo 0:ca84ed7518f5 103 i2c_.read(dev_id,data,2);
TanakaRobo 0:ca84ed7518f5 104 return (data[0] << 8) + data[1];
TanakaRobo 0:ca84ed7518f5 105 }