极客工坊

 找回密码
 注册

QQ登录

只需一步,快速开始

查看: 41347|回复: 8

I2C与串口通讯的冲突

[复制链接]
发表于 2015-8-27 22:37:39 | 显示全部楼层 |阅读模式
可以正常使用的APC220收发程序。多次测试没有问题。。。

但是将接收程序与mpu6050的滤波程序结合起来以后就得不到发送的值。大家帮忙看看,找找原因。

  1. /* Copyright (C) 2012 Kristian Lauszus, TKJ Electronics. All rights reserved.

  2. This software may be distributed and modified under the terms of the GNU
  3. General Public License version 2 (GPL2) as published by the Free Software
  4. Foundation and appearing in the file GPL2.TXT included in the packaging of
  5. this file. Please note that GPL2 Section 2[b] requires that all works based
  6. on this software must also be made publicly available under the terms of
  7. the GPL2 ("Copyleft").

  8. Contact information
  9. -------------------

  10. Kristian Lauszus, TKJ Electronics
  11. Web : http://www.tkjelectronics.com
  12. e-mail : [email][email protected][/email]
  13. */

  14. #include <Wire.h> //mpu6050和arduino通过I2C通信,所以要包含这个库
  15. #include <Kalman.h> //卡尔曼滤波函数
  16. #define RESTRICT_PITCH
  17. Kalman kalmanX; // 对X,Y轴创建卡尔曼实例
  18. Kalman kalmanY;
  19. double val,Val=0;
  20. /* IMU Data */
  21. double accX, accY, accZ;
  22. double gyroX, gyroY, gyroZ;//从mpu6050读出的六个数据

  23. double gyroXangle, gyroYangle; // Angle calculate using the gyro only
  24. double compAngleX, compAngleY; // Calculated angle using a complementary filter
  25. double kalAngleX, kalAngleY; // Calculated angle using a Kalman filter
  26. double angleX, angleY, angle, angleZ; //finall angle
  27. uint32_t timer;
  28. uint8_t i2cData[14]; // Buffer for I2C data

  29. // TODO: Make calibration routine

  30. void setup() {
  31.   Serial.begin(9600);
  32.   //if (Serial.available() > 0)
  33.    //val = Serial.read();
  34. Wire.begin();
  35. #if ARDUINO >= 157
  36. Wire.setClock(400000UL); // Set I2C frequency to 400kHz
  37. #else
  38. TWBR = ((F_CPU / 400000UL) - 16) / 2; // Set I2C frequency to 400kHz
  39. #endif

  40. i2cData[0] = 7; // Set the sample rate to 1000Hz - 8kHz/(7+1) = 1000Hz
  41. i2cData[1] = 0x00; // Disable FSYNC and set 260 Hz Acc filtering, 256 Hz Gyro filtering, 8 KHz sampling
  42. i2cData[2] = 0x00; // Set Gyro Full Scale Range to ±250deg/s
  43. i2cData[3] = 0x00; // Set Accelerometer Full Scale Range to ±2g
  44. while (i2cWrite(0x19, i2cData, 4, false)); // Write to all four registers at once
  45. while (i2cWrite(0x6B, 0x01, true)); // PLL with X axis gyroscope reference and disable sleep mode

  46. while (i2cRead(0x75, i2cData, 1));
  47. if (i2cData[0] != 0x68) { // Read "WHO_AM_I" register
  48. Serial.print(F("Error reading sensor"));
  49. while (1);
  50. }

  51. delay(100); // Wait for sensor to stabilize

  52. /* Set kalman and gyro starting angle */
  53. while (i2cRead(0x3B, i2cData, 6));
  54. accX = (i2cData[0] << 8) | i2cData[1];
  55. accY = (i2cData[2] << 8) | i2cData[3];
  56. accZ = (i2cData[4] << 8) | i2cData[5];

  57. // Source: http://www.freescale.com/files/sensors/doc/app_note/AN3461.pdf eq. 25 and eq. 26
  58. // atan2 outputs the value of -π to π (radians) - see http://en.wikipedia.org/wiki/Atan2
  59. // It is then converted from radians to degrees
  60. #ifdef RESTRICT_PITCH // Eq. 25 and 26
  61. double roll = atan2(accY, accZ) * RAD_TO_DEG;
  62. double pitch = atan(-accX / sqrt(accY * accY + accZ * accZ)) * RAD_TO_DEG;
  63. #else // Eq. 28 and 29
  64. double roll = atan(accY / sqrt(accX * accX + accZ * accZ)) * RAD_TO_DEG;
  65. double pitch = atan2(-accX, accZ) * RAD_TO_DEG;
  66. #endif

  67. kalmanX.setAngle(roll); // Set starting angle
  68. kalmanY.setAngle(pitch);
  69. gyroXangle = roll;
  70. gyroYangle = pitch;
  71. compAngleX = roll;
  72. compAngleY = pitch;

  73. //Calibration();
  74. timer = micros();
  75. }

  76. void loop() {
  77.   //if (Serial.available() > 0)
  78.   // val = Serial.read();
  79. double ret(double x);
  80. /* Update all the values */
  81. while (i2cRead(0x3B, i2cData, 14));
  82. accX = ((i2cData[0] << 8) | i2cData[1]);
  83. accY = ((i2cData[2] << 8) | i2cData[3]);
  84. accZ = ((i2cData[4] << 8) | i2cData[5]);
  85. //tempRaw = (i2cData[6] << 8) | i2cData[7];
  86. gyroX = (i2cData[8] << 8) | i2cData[9];
  87. gyroY = (i2cData[10] << 8) | i2cData[11];
  88. gyroZ = (i2cData[12] << 8) | i2cData[13];

  89. double dt = (double)(micros() - timer) / 1000000; // Calculate delta time
  90. timer = micros();

  91. // Source: http://www.freescale.com/files/sensors/doc/app_note/AN3461.pdf eq. 25 and eq. 26
  92. // atan2 outputs the value of -π to π (radians) - see http://en.wikipedia.org/wiki/Atan2
  93. // It is then converted from radians to degrees
  94. #ifdef RESTRICT_PITCH // Eq. 25 and 26
  95. double roll = atan2(accY, accZ) * RAD_TO_DEG;
  96. double pitch = atan(-accX / sqrt(accY * accY + accZ * accZ)) * RAD_TO_DEG;
  97. #else // Eq. 28 and 29
  98. double roll = atan(accY / sqrt(accX * accX + accZ * accZ)) * RAD_TO_DEG;
  99. double pitch = atan2(-accX, accZ) * RAD_TO_DEG;
  100. #endif

  101. double gyroXrate = gyroX / 131.0; // Convert to deg/s
  102. double gyroYrate = gyroY / 131.0; // Convert to deg/s

  103. #ifdef RESTRICT_PITCH
  104. // This fixes the transition problem when the accelerometer angle jumps between -180 and 180 degrees
  105. if ((roll < -90 && kalAngleX > 90) || (roll > 90 && kalAngleX < -90)) {
  106. kalmanX.setAngle(roll);
  107. compAngleX = roll;
  108. kalAngleX = roll;
  109. gyroXangle = roll;
  110. } else
  111. kalAngleX = kalmanX.getAngle(roll, gyroXrate, dt); // Calculate the angle using a Kalman filter

  112. if (abs(kalAngleX) > 90)
  113. gyroYrate = -gyroYrate; // Invert rate, so it fits the restriced accelerometer reading
  114. kalAngleY = kalmanY.getAngle(pitch, gyroYrate, dt);
  115. #else
  116. // This fixes the transition problem when the accelerometer angle jumps between -180 and 180 degrees
  117. if ((pitch < -90 && kalAngleY > 90) || (pitch > 90 && kalAngleY < -90)) {
  118. kalmanY.setAngle(pitch);
  119. compAngleY = pitch;
  120. kalAngleY = pitch;
  121. gyroYangle = pitch;
  122. } else
  123. kalAngleY = kalmanY.getAngle(pitch, gyroYrate, dt); // Calculate the angle using a Kalman filter

  124. if (abs(kalAngleY) > 90)
  125. gyroXrate = -gyroXrate; // Invert rate, so it fits the restriced accelerometer reading
  126. kalAngleX = kalmanX.getAngle(roll, gyroXrate, dt); // Calculate the angle using a Kalman filter
  127. #endif

  128. gyroXangle += gyroXrate * dt; // Calculate gyro angle without any filter
  129. gyroYangle += gyroYrate * dt;
  130. angle += gyroZ * dt / 131.0;

  131. gyroXangle += kalmanX.getRate() * dt; // Calculate gyro angle using the unbiased rate
  132. gyroYangle += kalmanY.getRate() * dt;

  133. compAngleX = 0.93 * (compAngleX + gyroXrate * dt) + 0.07 * roll; // Calculate the angle using a Complimentary filter
  134. compAngleY = 0.93 * (compAngleY + gyroYrate * dt) + 0.07 * pitch;

  135. // Reset the gyro angle when it has drifted too much
  136. if (gyroXangle < -180 || gyroXangle > 180)
  137. gyroXangle = kalAngleX;
  138. if (gyroYangle < -180 || gyroYangle > 180)
  139. gyroYangle = kalAngleY;

  140. angleX = kalAngleX - 2.32;
  141. angleY = kalAngleY + 0.38;
  142. angleZ = angle + 5;
  143. Val = ret(val);

  144. /* Print Data */
  145. #if 0 // Set to 1 to activate
  146. Serial.print(accX); Serial.print(",");
  147. Serial.print(accY); Serial.print(",");
  148. Serial.print(accZ); Serial.print(",");
  149. //Serial.print(tempRaw); Serial.print(",");
  150. Serial.print(gyroX / 131.0); Serial.print(",");
  151. Serial.print(gyroY / 131.0); Serial.print(",");
  152. Serial.print(gyroZ / 131.0); Serial.print(",");

  153. Serial.print("\t");
  154. #endif
  155. Serial.println(Val);// Serial.print(",");
  156. //Serial.print(roll); Serial.print("\t");
  157. //Serial.print(gyroXangle); Serial.print("\t");
  158. //Serial.print(compAngleX); Serial.print("\t");
  159. //Serial.print(angleX); Serial.print(",");

  160. //Serial.print("\t");

  161. //Serial.print(pitch); Serial.print("\t");
  162. //Serial.print(gyroYangle); Serial.print("\t");
  163. //Serial.print(compAngleY); Serial.print("\t");
  164. //Serial.print(angleY); Serial.print(",");
  165. //Serial.print(angleZ); Serial.println(",");

  166. }
  167. double ret(double x)
  168. {  
  169.   if(Serial.available()>0){
  170.   x=Serial.read();
  171.   }
  172.   return(x);
  173. }
复制代码
还有一个I2C的文件
const uint8_t IMUAddress = 0x68; // AD0 is logic low on the PCB
const uint16_t I2C_TIMEOUT = 1000; // Used to check for errors in I2C communication

uint8_t i2cWrite(uint8_t registerAddress, uint8_t data, bool sendStop) {
  return i2cWrite(registerAddress, &data, 1, sendStop); // Returns 0 on success
}

uint8_t i2cWrite(uint8_t registerAddress, uint8_t *data, uint8_t length, bool sendStop) {
  Wire.beginTransmission(IMUAddress);
  Wire.write(registerAddress);
  Wire.write(data, length);
  uint8_t rcode = Wire.endTransmission(sendStop); // Returns 0 on success
  if (rcode) {
    Serial.print(F("i2cWrite failed: "));
    Serial.println(rcode);
  }
  return rcode; // See: http://arduino.cc/en/Reference/WireEndTransmission
}

uint8_t i2cRead(uint8_t registerAddress, uint8_t *data, uint8_t nbytes) {
  uint32_t timeOutTimer;
  Wire.beginTransmission(IMUAddress);
  Wire.write(registerAddress);
  uint8_t rcode = Wire.endTransmission(false); // Don't release the bus
  if (rcode) {
    Serial.print(F("i2cRead failed: "));
    Serial.println(rcode);
    return rcode; // See: http://arduino.cc/en/Reference/WireEndTransmission
  }
  Wire.requestFrom(IMUAddress, nbytes, (uint8_t)true); // Send a repeated start and then release the bus after reading
  for (uint8_t i = 0; i < nbytes; i++) {
    if (Wire.available())
      data = Wire.read();
    else {
      timeOutTimer = micros();
      while (((micros() - timeOutTimer) < I2C_TIMEOUT) && !Wire.available());
      if (Wire.available())
        data = Wire.read();
      else {
        Serial.println(F("i2cRead timeout"));
        return 5; // This error value is not already taken by endTransmission
      }
    }
  }
  return 0; // Success
}

还有两个.h和.cpp文件,以及上面的程序我都做个打包压缩。

本帖子中包含更多资源

您需要 登录 才可以下载或查看,没有帐号?注册

x
回复

使用道具 举报

 楼主| 发表于 2015-8-27 22:40:22 | 显示全部楼层
最后一张图片跟主题没有关系,手残了一下,不要意思。
回复 支持 反对

使用道具 举报

发表于 2015-8-28 09:52:17 | 显示全部楼层
化简程序吧,太长了不会有人给你看的

回复 支持 反对

使用道具 举报

发表于 2015-8-30 10:48:26 | 显示全部楼层
查延时吧,串口数据读取其实是内部中断控制的,程序块内耗费时间太长,串口就无法正常工作。
回复 支持 反对

使用道具 举报

 楼主| 发表于 2015-9-3 23:42:33 | 显示全部楼层
嗯,其实也这么想过,但是不知从何下手
回复 支持 反对

使用道具 举报

发表于 2015-9-15 10:13:21 | 显示全部楼层
所有delay()的地方都检查下,添加些串口检测之类的函数……
回复 支持 反对

使用道具 举报

 楼主| 发表于 2015-10-10 01:02:18 | 显示全部楼层
已经搞好了,没能及时回你,是我没搞清楚串口通讯的语法,
回复 支持 反对

使用道具 举报

发表于 2017-5-21 23:27:20 | 显示全部楼层
持梦追寻 发表于 2015-10-10 01:02
已经搞好了,没能及时回你,是我没搞清楚串口通讯的语法,

你咋解决的,能说一下吗?
回复 支持 反对

使用道具 举报

发表于 2020-12-14 19:12:24 | 显示全部楼层
持梦追寻 发表于 2015-10-10 01:02
已经搞好了,没能及时回你,是我没搞清楚串口通讯的语法,

是怎么解决多块从机通信的问题的呢?
我的1主机2从机   从机1还正常,从机2就不正常了,
大神  可以帮我看看我的I2C通信问题吗?谢谢了
传送门:https://www.geek-workshop.com/thread-39910-1-1.html
回复 支持 反对

使用道具 举报

您需要登录后才可以回帖 登录 | 注册

本版积分规则 需要先绑定手机号

Archiver|联系我们|极客工坊

GMT+8, 2024-4-24 02:44 , Processed in 0.057345 second(s), 23 queries .

Powered by Discuz! X3.4 Licensed

Copyright © 2001-2021, Tencent Cloud.

快速回复 返回顶部 返回列表