PART- 11: 平衡

這個課題估計我要學好幾年了,
試用了一堆板子,讀了一堆文章,最後選定了 MultiWii 來當做教材.
http://www.multiwii.com ) 
(超級風行的 UAV 學習課題,學問超級多,範圍超級廣,每個功能都是一門專業的學問)
控制板: MultiWii All In One 主板
( Arduino Mega 2560, MPU6050, HMC5883L,MS5611 )


飛行機構: 泰世-四軸飛行器 330X
說明書中提到可以控制的多軸飛行器種類如下:



  



BiCopter就是俗稱的 阿凡達啦~

Sensor 讀到信號了,除了 GPS沒時間玩, 現在都到齊了..
本來只要 ACC, GYRO, MAG, AHRS, 
現在多了 高度計..
有圖有真相喔 .. (要學的東西好多阿~~ 爽~)

因為重要的零件等待從德國飛來,
先來學習一下機構相關的設計..
算是番外篇吧.. 看圖:

片身+凹巢然後用鋁柱+螺絲強化結構,組成立體的機身,
看來我機器人的機構也可以自己用CNC這樣製作..


加上馬達後,覺得也是很堅固耶~

另外一個好東西,從法國寄來的,
Arduino Mini Pro ready to use.

也要開始 機構設計了...
第一步: 先把要用的 Servo 模型建出來,
本來按照著 說明書的尺寸做,
結果servo拿出來發現~~~~ 怎麼標示的不一樣@@
原來螺絲是不標出來的..呵呵~



用 SketchUp 畫出 servo model

用這個 servo的模型為基礎, 開始先在 SketchUp 設計心中的機器人,
這樣尺寸才會符合~

剛剛收到了,
從德國漢堡寄來的 FreeIMU 最新版 0.4.3
我要將這用在我機器人的 "平衡中樞".
看圖嚕~
終於全部的零件都到齊...要開始整合了,
要做的事情還真多~ 全部靠自己一個人做,
不知何年何月才能實現夢想阿~_~

有同好要一起圓夢的嗎? 

做好的 servo 模型,
放到 Unity3D 裡面,
把 servo 指定軸向連接...
先暫時做個模擬影片.
影片:

更新一下.. FreeIMU 0.4.3的效果,
現在存在一個 bug.. Yaw會飄移...
影片:
今天是 2012-09-17 先不要買這個版..
等解決後再買..
已經有校正Yaw的解決方案了, 
只是需要時間移植程式到 Arduino LIB


要採用 鋰電池當做機器人的電源,
就當買個保險.. 一個好物 - "鋰電警報器",
低電壓的時候會大叫~ ~

背面照:








正面:













組裝, 接線... (好亂的桌面...該整理了)
四顆同時叫還真是有趣,
實機看起來好小,也就兩個手掌大..
接下來測試馬達轉向/位置, RC Channel, LED...等的接線正確性...



附帶一題...新手請勿急著安裝 "槳"... 會變血滴子,
貼張貼紙在馬達軸上就可以看出轉向了.. 
千萬注意安全,這不是玩具,是殺人飛行器...
就像機器人的 servo 一樣, 夾到手指也是很痛的 @@


另外一個好物到了... SSC-32,
這是第二版的.














要用 Arduino Uno 連接 SSC-32 同時控制 32顆 servo,
先貼上接線圖說明..
直接接電腦就可以控制,要插上2個jump




要接 Arduino,拔掉上面 2個jump,
只要兩條線.. SSC-32的 RX 接到 Arduino 的 TX, 然後共地.







露天牌 9dof 終於測試出正確的接腳了... = =
看圖吧~





如果有人買到的話, 參考我的接腳吧 ...
只要四條線就可以了,
Arduino           露天牌 9dof 
+5V                +5V
GND                GND
A4                   SDA
A5                   SCL
就是你看的懂英文字的那四個 @@

今天忍不住先全部 Servo 同時啟動...
重溫當年第一次狼狽爬樓梯的感動了,
馬上要機體大改了... 留張遺照 = =









目前測試過比較好的是 AHRS..
使用的是:
露天牌 9 DOF IMU
陀螺儀ITG3205/ITG3200
加速度計ADXL345
數位羅盤HMC5883L

看起來不會飄移了, 但是還要再嚴格的測試.
影片:






實際上我的磁場偏移嚴重,需要校準..
位處於地球的某的地方都會需要加入偏移值..


















到 美國國家地球物理中心 http://www.ngdc.noaa.gov
查詢台北的位置結果..














這是我用 iPhone 顯示的..





PART 10: Wii motion plus + Nunchuck (Kalman Filter)

我知道這已經過時很久了,
但是我蹺課太久了,現在捕回來@@
找到下列程式有一個重點,就是經過了 "Kalman Filter"的計算,
這樣才能夠實際應用, 不然一堆雜訊是沒辦法用的.
但是如果要更好的效果, 就要選用 9DOF IMU,
搭配Compass一起計算...這是後面的課題了..


// Modified Kalman code using the Y-Axis from a Wii MotionPlus and the X and Z from a Nunchuck.
// Nunchuck joystick provides corrections - X for Gyro, Y for Accelerometer
// Also uses "new" style Init to provide unencrypted data from the Nunchuck to avoid the XOR on each byte.
// Requires the WM+ and Nunchuck to be connected to Arduino pins D3/D4 using the schematic from Knuckles904
// See http://randomhacksofboredom.blogspot.com/2009/07/motion-plus-and-nunchuck-together-on.html
// Kalman Code Originally By Jordi Munoz... //Si deseas la version en Espanol, no dudes en escribirme...
//
// Altered by Adrian Carter <adrian@canberrariders.org.au> to work with WiiM+ and Nunchuck

#include <math.h>
#include <Wire.h>
/////////////////////////////////////////
#define NUMREADINGS 5 //Gyro noise filter
// test for 3 axis
int readingsX[NUMREADINGS];
int readingsY[NUMREADINGS];
int readingsZ[NUMREADINGS];                    // the readings
int totalX = 0;
int totalY = 0;
int totalZ = 0;                                   // the running total
int averageX = 0;                                  // the average
int averageY = 0;
int averageZ = 0;
int lastaverageZ =0;
// End of 3 axis stuff
int readings[NUMREADINGS];                    // the readings from the analog input (gyro)
int index = 0;                                    // the index of the current reading
int total = 0;                                    // the running total
int average = 0;                                  // the average
int inputPin =0;                                  // Gyro Analog input
//WM+ stuff
byte data[6]; //six data bytes
int yaw, pitch, roll; //three axes
int yaw0, pitch0, roll0; //calibration zeroes
///////////////////////////////////////

float        dt        = .06; //( 1024.0 * 256.0 ) / 16000000.0; (Kalman)
int mydt = 20; //in ms.
static float                P[2][2] = { //(Kalman)

  {
    1, 0   }
  , //(Kalman)
  {
    0, 1   }
  ,//(Kalman)
}; //(Kalman)
// extra 2 axis..
static float                P1[2][2] = {  { 1, 0 } ,  { 0, 1 } ,};
static float                P2[2][2] = {  { 1, 0 } ,  { 0, 1 } ,};
static float                P3[2][2] = {  { 1, 0 } ,  { 0, 1 } ,}; //(Kalman)


/*
 * Our two states, the angle and the gyro bias.  As a byproduct of computing
 * the angle, we also have an unbiased angular rate available.   These are
 * read-only to the user of the module.
 */
float                        angle; //(Kalman)
float                         angleX;
float                         angleY;
float                         angleZ;
float                        q_bias; //(Kalman)
float                         q_bias_X;
float                         q_bias_Y;
float                         q_bias_Z;
float                         rate_X;
float                         rate_Y;
float                         rate_Z;
float                         q_m_X; //(Kalman)
float                         q_m_Y;
float                         q_m_Z;
float                         rotationZ;
float                        rate; //(Kalman)
float                         q_m; //(Kalman)

// adjusts
int gyro_adjust = 1;
int accel_adjust = 128;

int joy_x_axis = 0; //NunChuck Joysticks potentiometers
int joy_y_axis = 0;
int ax_m=0;        //NunChuck X acceleration
// Re-added Y Axis
int ay_m=0;        //NunChuck Y acceleration
int az_m=0;        //NunChuck Z acceleration
byte outbuf[6];                // array to store arduino output
int cnt = 0;                //Counter
unsigned long lastread=0;

/*
 * R represents the measurement covariance noise.  In this case,
 * it is a 1x1 matrix that says that we expect 0.3 rad jitter
 * from the accelerometer.
 */
float        R_angle        = .3; //.3 deafault, but is adjusted externally (Kalman)


/*
 * Q is a 2x2 matrix that represents the process covariance noise.
 * In this case, it indicates how much we trust the acceleromter
 * relative to the gyros.
 */
static const float        Q_angle        = 0.001; //(Kalman)
static const float        Q_gyro        = 0.003; //(Kalman)

void switchtonunchuck(){
/*  PORTE ^= 32; // Toggle D3 LOW
  PORTG |= 32; // Force D4 HIGH */ // Fast switching of pins... Arduino MEGA specific...
digitalWrite(3, LOW);
digitalWrite(4, LOW);
digitalWrite(4, HIGH);

}

void switchtowmp(){
/*  PORTG ^= 32; // Toggle D4 LOW
  PORTE |= 32; // Force D3 HIGH */ // Fast switching of pins... Arduino MEGA Specific pin maps, so switched back to 'normal' code for example
digitalWrite(3, LOW);
digitalWrite(4, LOW);
digitalWrite(3, HIGH);
}

void nunchuck_init () //(nunchuck)
{
// Uses New style init - no longer encrypted so no need to XOR bytes later... might save some cycles
 Wire.beginTransmission (0x52);        // transmit to device 0x52
  Wire.write (0xF0);                // sends memory address
  Wire.write (0x55);                // sends sent a zero.
  Wire.endTransmission ();        // stop transmitting
  delay(100);
  Wire.beginTransmission (0x52);        // transmit to device 0x52
  Wire.write (0xFB);                // sends memory address
  Wire.write (0x00);                // sends sent a zero.
  Wire.endTransmission ();        // stop transmitting
}

void setup()
{
  Serial.begin(115200);
/*  DDRG |= 32; // Force D3 to Output // Arduino MEGA "fast" pin config. Reverted to 'normal' for example post.
  DDRE |= 32; // Force D4 to Output
  PORTG ^= 32; // Toggle D3 HIGH
  PORTE ^= 32; // Toggle D4 HIGH */

  pinMode(3, OUTPUT);
  pinMode(4, OUTPUT);
  digitalWrite(3, HIGH);
  digitalWrite(4, HIGH);

  Wire.begin ();                // join i2c bus with address 0x52 (nunchuck)
  switchtowmp();
  wmpOn();
  calibrateZeroes();
  switchtonunchuck();
  nunchuck_init (); // send the initilization handshake

  for (int i = 0; i < NUMREADINGS; i++)
    readings[i] = 0;                            // initialize all the readings to 0 (gyro average filter)
}

void send_zero () //(nunchuck)
{
  Wire.beginTransmission (0x52);        // transmit to device 0x52 (nunchuck)
  Wire.write (0x00);                // sends one byte (nunchuck)
  Wire.endTransmission ();        // stop transmitting (nunchuck)
}

void wmpOn(){
Wire.beginTransmission(0x53);//WM+ starts out deactivated at address 0x53
Wire.write(0xfe); //send 0x04 to address 0xFE to activate WM+
Wire.write(0x04);
Wire.endTransmission(); //WM+ jumps to address 0x52 and is now active
}

void wmpOff(){
Wire.beginTransmission(82);
Wire.write(0xf0);//address then
Wire.write(0x55);//command
Wire.endTransmission();
}

void wmpSendZero(){
Wire.beginTransmission(0x52);//now at address 0x52
Wire.write(0x00); //send zero to signal we want info
Wire.endTransmission();
}

void calibrateZeroes(){
for (int i=0;i<10;i++){
wmpSendZero();
Wire.requestFrom(0x52,6);
for (int i=0;i<6;i++){
data[i]=Wire.read();
}
yaw0+=(((data[3] >> 2) << 8)+data[0])/10;//average 10 readings
pitch0+=(((data[4] >> 2) << 8)+data[1])/10;// for each zero
roll0+=(((data[5] >> 2) << 8)+data[2])/10;
}
}

void receiveData(){
wmpSendZero(); //send zero before each request (same as nunchuck)
Wire.requestFrom(0x52,6); //request the six bytes from the WM+
for (int i=0;i<6;i++){
data[i]=Wire.read();
}
//see http://wiibrew.org/wiki/Wiimote/Extension_Controllers#Wii_Motion_Plus
//for info on what each byte represents
yaw=((data[3] >> 2) << 8)+data[0]-yaw0;
pitch=((data[4] >> 2) << 8)+data[1]-pitch0;
roll=((data[5] >> 2) << 8)+data[2]-roll0;
}

void receiveRaw(){
wmpSendZero(); //send zero before each request (same as nunchuck)
Wire.requestFrom(0x52,6);//request the six bytes from the WM+
for (int i=0;i<6;i++){
data[i]=Wire.read();
}
yaw=((data[3] >> 2) << 8)+data[0];
pitch=((data[4] >> 2) << 8)+data[1];
roll=((data[5] >> 2) << 8)+data[2];
}


void loop()
{
  if((millis()-lastread) >= mydt) { // sample every dt ms -> 1000/dt hz.
    lastread = millis();
    total += readings[index];
    totalX += readingsX[index];
    totalY += readingsY[index];
    totalZ += readingsZ[index];                   // add the reading to the total
    switchtowmp();
    receiveData();
    switchtonunchuck();
    readings[index] = int(pitch/20); // read from the gyro sensor (/20 to get degree/second) pitch == roll
    readingsX[index] = int(yaw/20); // read from the gyro sensor (/20 to get degree/second) pitch == roll
//Continued
    readingsX[index] = int(roll/20); // read from the gyro sensor (/20 to get degree/second) pitch == roll
    readingsY[index] = int(pitch/20); // read from the gyro sensor (/20 to get degree/second) pitch == roll
    readingsZ[index] = int(yaw/20); // read from the gyro sensor (/20 to get degree/second) pitch == roll
//    receiveRaw(); // Provides unbiased output from WM+ (i.e, without calibrationZeros)


    index = (index + 1);                          // advance to the next index

    if (index >= NUMREADINGS)                   // if we're at the end of the array...
        index = 0;                                    // ...wrap around to the beginning

    average = (total / NUMREADINGS) - 511;
    averageX = (totalX / NUMREADINGS) - 511;
    averageY = (totalY / NUMREADINGS) - 511;
    averageZ = (totalZ / NUMREADINGS) - 511;    // calculate the average of gyro input

    q_m=((average*(joy_x_axis*0.00392156862))/(180/PI)); //GYRO convertion to Radian and external correction with nunchuk joystick
    q_m_X=((averageX*(joy_x_axis*0.00392156862))/(180/PI)); //GYRO convertion to Radian and external correction with nunchuk joystick
    q_m_Y=((averageY*(joy_x_axis*0.00392156862))/(180/PI)); //GYRO convertion to Radian and external correction with nunchuk joystick
    q_m_Z=((averageZ*(joy_x_axis*0.00392156862))/(180/PI)); //GYRO convertion to Radian and external correction with nunchuk joystick

    /* Unbias our gyro */
    const float        q_X = q_m_X - q_bias_X; //(Kalman)
    const float q_Y = q_m_Y - q_bias_Y;
    const float q_Z = q_m_Z - q_bias_Z;
    const float        q = q_m - q_bias; //(Kalman)

    const float                Pdot[2 * 2] = {
        Q_angle - P[0][1] - P[1][0],        /* 0,0 */ //(Kalman)
        - P[1][1],                /* 0,1 */
        - P[1][1],                /* 1,0 */
        Q_gyro                                /* 1,1 */
    };

     const float        PdotX[2 * 2] = {
        Q_angle - P1[0][1] - P1[1][0],        /* 0,0 */ //(Kalman)
        - P1[1][1],                          /* 0,1 */
        - P1[1][1],                          /* 1,0 */
        Q_gyro                                /* 1,1 */
    };

    const float        PdotY[2 * 2] = {
        Q_angle - P2[0][1] - P2[1][0],        /* 0,0 */ //(Kalman)
        - P2[1][1],                          /* 0,1 */
        - P2[1][1],                          /* 1,0 */
        Q_gyro                                /* 1,1 */
    };

    const float        PdotZ[2 * 2] = {
        Q_angle - P3[0][1] - P3[1][0],        /* 0,0 */ //(Kalman)
        - P3[1][1],                          /* 0,1 */
        - P3[1][1],                          /* 1,0 */
        Q_gyro                                /* 1,1 */
    };

    /* Store our unbias gyro estimate */
    rate = q; //(Kalman)
    rate_X = q_X; //(Kalman)
    rate_Y = q_Y;
    rate_Z = q_Z;

    /*
         * Update our angle estimate
              * angle += angle_dot * dt
              *         += (gyro - gyro_bias) * dt
              *         += q * dt
              */
    angle += q * dt; //(Kalman)
    angleX += q_X * dt; //(Kalman)
    angleY += q_Y * dt;
    angleZ += q_Z * dt;

    /* Update the covariance matrix */
    P[0][0] += Pdot[0] * dt; //(Kalman)
    P[0][1] += Pdot[1] * dt; //(Kalman)
    P[1][0] += Pdot[2] * dt; //(Kalman)
    P[1][1] += Pdot[3] * dt; //(Kalman)

    P1[0][0] += PdotX[0] * dt; //(Kalman) X axis
    P1[0][1] += PdotX[1] * dt; //(Kalman)
    P1[1][0] += PdotX[2] * dt; //(Kalman)
    P1[1][1] += PdotX[3] * dt; //(Kalman)

    P2[0][0] += PdotY[0] * dt;//y axis
    P2[0][1] += PdotY[1] * dt;
    P2[1][0] += PdotY[2] * dt;
    P2[1][1] += PdotY[3] * dt;

    P3[0][0] += PdotZ[0] * dt;//y axis
    P3[0][1] += PdotZ[1] * dt;
    P3[1][0] += PdotZ[2] * dt;
    P3[1][1] += PdotZ[3] * dt;

    Wire.requestFrom (0x52, 6);        // request data from nunchuck

    while (Wire.available ()) //(NunChuck)
    {
        outbuf[cnt] = Wire.read ();        // receive byte as an integer //(NunChuck)
        cnt++;//(NunChuck)
    }

    send_zero (); // send the request for next bytes
    // If we recieved the 6 bytes, then print them //(NunChuck)
    if (cnt >= 5) //(NunChuck)
    {
        print (); //(NunChuck)
    }
    cnt = 0; //(NunChuck)

    R_angle= (joy_y_axis+1)*0.0098039; //external adjust jitter of accelerometer with nunchuck joystick


    const float                angle_m = atan2( ax_m, az_m ); //(Kalman)
    const float                angle_err = angle_m - angle; //(Kalman)
    const float                C_0 = 1; //(Kalman)
    const float                PCt_0 = C_0 * P[0][0];  //(Kalman)
    const float                PCt_1 = C_0 * P[1][0]; //(Kalman)
    const float                E =R_angle+ C_0 * PCt_0; //(Kalman)
    const float                K_0 = PCt_0 / E; //(Kalman)
    const float                K_1 = PCt_1 / E; //(Kalman)
    const float                t_0 = PCt_0; /* C_0 * P[0][0] + C_1 * P[1][0] (Kalman) */

    const float                t_1 = C_0 * P[0][1]; /* + C_1 * P[1][1]  = 0 (Kalman) */


    P[0][0] -= K_0 * t_0; //(Kalman)
    P[0][1] -= K_0 * t_1; //(Kalman)
    P[1][0] -= K_1 * t_0; //(Kalman)
    P[1][1] -= K_1 * t_1; //(Kalman)
    angle        += K_0 * angle_err; //(Kalman)
    q_bias        += K_1 * angle_err; //(Kalman)

          const float                angle_mX = atan2( ax_m, az_m ); //(Kalman) X axis
    const float                angle_errX = angle_mX - angleX; //(Kalman) X axis
    const float                C_0_1 = 1; //(Kalman) X axis
    const float                PCt_0_1 = C_0_1 * P[0][0];  //(Kalman)
    const float                PCt_1_1 = C_0_1 * P[1][0]; //(Kalman)
    const float                E_1 =R_angle+ C_0_1 * PCt_0_1; //(Kalman)
    const float                K_0_1 = PCt_0_1 / E_1; //(Kalman)
    const float                K_1_1 = PCt_1_1 / E_1; //(Kalman)
    const float                t_0_1 = PCt_0_1; /* C_0_1 * P[0][0] + C_1 * P[1][0] (Kalman) */
    const float                t_1_1 = C_0_1 * P[0][1]; /* + C_1 * P[1][1]  = 0 (Kalman) */


    P1[0][0] -= K_0_1 * t_0_1; //(Kalman)
    P1[0][1] -= K_0_1 * t_1_1; //(Kalman)
    P1[1][0] -= K_1_1 * t_0_1; //(Kalman)
    P1[1][1] -= K_1_1 * t_1_1; //(Kalman)
    angleX        += K_0_1 * angle_errX; //(Kalman)
    q_bias_X        += K_1_1 * angle_errX; //(Kalman)


    const float           angle_mY = atan2( ay_m, az_m );  // y axis
    const float           angle_errY = angle_mY - angleY;  // y axis
    const float           C_0_2 = 1;
    const float           PCt_0_2 = C_0_2 * P2[0][0];
    const float           PCt_1_2 = C_0_2 * P2[1][0];
    const float           E_2 =R_angle+ C_0_2 * PCt_0_2;
    const float           K_0_2 = PCt_0_2 / E_2;
    const float           K_1_2 = PCt_1_2 / E_2;
    const float           t_0_2 = PCt_0_2;
    const float           t_1_2 = C_0_2 * P2[0][1];

    P2[0][0] -= K_0_2 * t_0_2;
    P2[0][1] -= K_0_2 * t_1_2;
    P2[1][0] -= K_1_2 * t_0_2;
    P2[1][1] -= K_1_2 * t_1_2;
    angleY += K_0_2 * angle_errY;
    q_bias_Y += K_1_2 * angle_errY;

    const float           angle_mZ = averageZ/5;
    const float           angle_errZ = angle_mZ - angleZ;
    const float           C_0_3 = 1;
    const float           PCt_0_3 = C_0_3 * P3[0][0];
    const float           PCt_1_3 = C_0_3 * P3[1][0];
    const float           E_3 =R_angle+ C_0_3 * PCt_0_3;
    const float           K_0_3 = PCt_0_3 / E_3;
    const float           K_1_3 = PCt_1_3 / E_3;
    const float           t_0_3 = PCt_0_3;
    const float           t_1_3 = C_0_3 * P3[0][1];

    P3[0][0] -= K_0_3 * t_0_3;
    P3[0][1] -= K_0_3 * t_1_3;
    P3[1][0] -= K_1_3 * t_0_3;
    P3[1][1] -= K_1_3 * t_1_3;
    angleZ += K_0_3 * angle_errZ;
    q_bias_Z += K_1_3 * angle_errZ;

    rotationZ = angleZ;

    Serial.print("average z ");Serial.print(averageZ);Serial.print("  lastaverage z ");Serial.println(lastaverageZ);
    Serial.print("  angle_mZ = "); Serial.println(int(angle_mZ * 57.2957795130823));
    Serial.print("Rate  ");Serial.print(int(rate*57.2957795130823)); Serial.print("  Angle X  "); Serial.print(int(angleX*57.2957795130823)); Serial.print("  Angle Y  "); Serial.println(int(angleY*57.2957795130823)); //Prints degrees Acceleromter+Gyros+KalmanFilters
    Serial.print(joy_y_axis); //Prints the adjust for accelerometer jitter
    Serial.print(" ");
    Serial.print(int(angle*57.2957795130823)); //Prints degrees Acceleromter+Gyros+KalmanFilters
    Serial.print(" ");
    Serial.print(int(angle_m*57.295779513082)); //Prints the accelometer
    Serial.print(" ");
    Serial.println(joy_x_axis); //Prints the Gyro adjusment
  }
}
void print ()//This is the function to get the bytes from nintendo wii nunchuck
{
  joy_x_axis = outbuf[0];
  joy_y_axis = outbuf[1];
  ax_m = (outbuf[2] * 2 * 2) -511; //Axis X Acceleromter
  ay_m = (outbuf[3] * 2 * 2) -511; //Axis Y Acceleromter
  az_m = (outbuf[4] * 2 * 2) -511; //Axis Z Acceleromter

  // byte outbuf[5] contains bits for z and c buttons
  // it also contains the least significant bits for the accelerometer data
  // so we have to check each bit of byte outbuf[5]


  if ((outbuf[5] >> 2) & 1)
  {
    ax_m += 2;
  }
  if ((outbuf[5] >> 3) & 1)
  {
    ax_m += 1;
  }

  if ((outbuf[5] >> 4) & 1)
   {
   ay_m += 2;
   }
   if ((outbuf[5] >> 5) & 1)
   {
   ay_m += 1;
   }

  if ((outbuf[5] >> 6) & 1)
  {
    az_m += 2;
  }
  if ((outbuf[5] >> 7) & 1)
  {
    az_m += 1;
  }


}




Part 9: 有刷馬達的控制


準備元件..
1. 有刷馬達.
2. 馬達控制器( pololu-Qik2s12v10 )




原始程式(來自 Pololu 官網)

/*
Required connections between Arduino and qik 2s12v10:

      Arduino   qik 2s12v10
---------------------------
          GND - GND
Digital Pin 2 - TX
Digital Pin 3 - RX
Digital Pin 4 - RESET

DO NOT connect the 5V output on the Arduino to the 5V output on the qik 2s12v10!
*/

#include <SoftwareSerial.h>
#include <PololuQik.h>

PololuQik2s12v10 qik(2, 3, 4);

void setup()
{
  Serial.begin(115200);
  Serial.println("qik 2s12v10 dual serial motor controller");

  qik.init();

  Serial.print("Firmware version: ");
  Serial.write(qik.getFirmwareVersion());
  Serial.println();
}

void loop()
{
  for (int i = 0; i <= 127; i++)
  {
    qik.setM0Speed(i);
    if (abs(i) % 64 == 32)
    {
      Serial.print("M0 current: ");
      Serial.println(qik.getM0CurrentMilliamps());
    }
    delay(5);
  }

  for (int i = 127; i >= -127; i--)
  {
    qik.setM0Speed(i);
    if (abs(i) % 64 == 32)
    {
      Serial.print("M0 current: ");
      Serial.println(qik.getM0CurrentMilliamps());
    }
    delay(5);
  }

  for (int i = -127; i <= 0; i++)
  {
    qik.setM0Speed(i);
    if (abs(i) % 64 == 32)
    {
      Serial.print("M0 current: ");
      Serial.println(qik.getM0CurrentMilliamps());
    }
    delay(5);
  }

  for (int i = 0; i <= 127; i++)
  {
    qik.setM1Speed(i);
    if (abs(i) % 64 == 32)
    {
      Serial.print("M1 current: ");
      Serial.println(qik.getM1CurrentMilliamps());
    }
    delay(5);
  }

  for (int i = 127; i >= -127; i--)
  {
    qik.setM1Speed(i);
    if (abs(i) % 64 == 32)
    {
      Serial.print("M1 current: ");
      Serial.println(qik.getM1CurrentMilliamps());
    }
    delay(5);
  }

  for (int i = -127; i <= 0; i++)
  {
    qik.setM1Speed(i);
    if (abs(i) % 64 == 32)
    {
      Serial.print("M1 current: ");
      Serial.println(qik.getM1CurrentMilliamps());
    }
    delay(5);
  }
}

http://youtu.be/kQzoKnWcxcM