Microduino的cube小车。

Dependencies:   mbed-rtos mbed

Files at this revision

API Documentation at this revision

Comitter:
lixianyu
Date:
Sat May 28 05:09:18 2016 +0000
Parent:
3:e4ac7c1a14de
Commit message:
??work????

Changed in this revision

Microduino_Motor.cpp Show annotated file Show diff for this revision Revisions of this file
Microduino_Motor.h Show annotated file Show diff for this revision Revisions of this file
Microduino_Protocol_HardSer.cpp Show annotated file Show diff for this revision Revisions of this file
Microduino_Protocol_HardSer.h Show annotated file Show diff for this revision Revisions of this file
Protocol.h Show annotated file Show diff for this revision Revisions of this file
main.cpp Show annotated file Show diff for this revision Revisions of this file
userDef.h Show annotated file Show diff for this revision Revisions of this file
diff -r e4ac7c1a14de -r 0670023d3f36 Microduino_Motor.cpp
--- a/Microduino_Motor.cpp	Fri May 27 01:44:31 2016 +0000
+++ b/Microduino_Motor.cpp	Sat May 28 05:09:18 2016 +0000
@@ -13,9 +13,10 @@
 #if 0
             pinMode( _motor_pinA, OUTPUT) ;
 #else
-            _period_us = 2000; // 500Hz
+            _period_us = 255; // 500Hz
             pwmout_init(&_pwmA, _motor_pinA);
             pwmout_period_us(&_pwmA, _period_us); // 500Hz
+            pwmout_pulsewidth_us(&_pwmA, 1);
 #endif
             motors[this->motorIndex].Pin.nbr_A = _motor_pinA;
 
@@ -24,6 +25,7 @@
 #else
             pwmout_init(&_pwmB, _motor_pinB);
             pwmout_period_us(&_pwmB, _period_us); // 500Hz
+            pwmout_pulsewidth_us(&_pwmB, 1);
 #endif
             motors[this->motorIndex].Pin.nbr_B = _motor_pinB;
 
@@ -39,21 +41,24 @@
     this->fix=_fix;
 }
 
-int16_t Motor::GetData(int16_t _throttle, int16_t _steering, bool _dir)
+int16_t Motor::GetData(int16_t _throttle, int16_t _steering, uint8_t _dir)
 {
     this->_motor_vol = _throttle;
 
-    if(_dir)
+    if(_dir == 1)
+    {
         this->_motor_vol -= _steering / 2;
+    }
     else
+    {
         this->_motor_vol += _steering / 2;
-
+    }
     if (this->_motor_vol > 255)
         this->_motor_vol = 255;
     else if (this->_motor_vol < -255)
         this->_motor_vol = -255;
 
-    this->_motor_vol *= fix;
+    //this->_motor_vol *= fix;
 
     return this->_motor_vol;
 }
@@ -77,21 +82,52 @@
 #else
 void Motor::Driver(int16_t _motor_driver)
 {
-    int16_t pulseWidth = 0;
-    PinName channel_A = motors[this->motorIndex].Pin.nbr_A;
-    PinName channel_B = motors[this->motorIndex].Pin.nbr_B;
+    //static bool flag = true;
+    uint32_t pulseWidth = 0;
+    //PinName channel_A = motors[this->motorIndex].Pin.nbr_A;
+    //PinName channel_B = motors[this->motorIndex].Pin.nbr_B;
+    #if 0
+    pwmout_pulsewidth_us(&_pwmA, _period_us/2);
+    pwmout_pulsewidth_us(&_pwmB, 0);
+    return;
+    #endif
+    #if 0
+    pwmout_pulsewidth_us(&_pwmA, 0);
+    pwmout_pulsewidth_us(&_pwmB, _period_us/2);
+    return;
+    #endif
     if (_motor_driver == 0) {
         pwmout_pulsewidth_us(&_pwmA, 0);
         pwmout_pulsewidth_us(&_pwmB, 0);
     } else if (_motor_driver > 0) {
-        pulseWidth = _period_us * _motor_driver / 255;
+        #if 1
+        pulseWidth = _period_us / 255 * _motor_driver;
         pwmout_pulsewidth_us(&_pwmA, pulseWidth);
+        pwmout_pulsewidth_us(&_pwmB, 2);
+        #else
+        pwmout_pulsewidth_us(&_pwmA, _period_us/2);
         pwmout_pulsewidth_us(&_pwmB, 0);
+        #endif
     } else {
+        #if 0
         _motor_driver = 255 + _motor_driver;
-        pulseWidth = _period_us * _motor_driver / 255;
-        pwmout_pulsewidth_us(&_pwmA, pulseWidth);
-        pwmout_pulsewidth_us(&_pwmB, _period_us);
+        pulseWidth = _period_us / 255 * _motor_driver;
+        pwmout_pulsewidth_us(&_pwmA, 0);
+        pwmout_pulsewidth_us(&_pwmB, pulseWidth);
+        #elif 1
+        _motor_driver = abs(_motor_driver);
+        pulseWidth = _period_us / 255 * _motor_driver;
+        pwmout_pulsewidth_us(&_pwmA, 2);
+        pwmout_pulsewidth_us(&_pwmB, pulseWidth);
+        #elif 0
+        _motor_driver = 255 + _motor_driver;
+        pulseWidth = _period_us / 255 * _motor_driver;
+        pwmout_pulsewidth_us(&_pwmA, _period_us);
+        pwmout_pulsewidth_us(&_pwmB, pulseWidth);
+        #else
+        pwmout_pulsewidth_us(&_pwmA, 0);
+        pwmout_pulsewidth_us(&_pwmB, 241);
+        #endif
     }
 }
 #endif
diff -r e4ac7c1a14de -r 0670023d3f36 Microduino_Motor.h
--- a/Microduino_Motor.h	Fri May 27 01:44:31 2016 +0000
+++ b/Microduino_Motor.h	Sat May 28 05:09:18 2016 +0000
@@ -32,7 +32,7 @@
     void Driver(int16_t _motor_driver);
     void Free();
     void Brake();
-    int16_t GetData(int16_t _throttle, int16_t _steering, bool _dir);
+    int16_t GetData(int16_t _throttle, int16_t _steering, uint8_t _dir);
 private:
     uint8_t motorIndex;               // index into the channel data for this key
     float fix;
@@ -40,7 +40,7 @@
 protected:
     pwmout_t _pwmA;
     pwmout_t _pwmB;
-    uint16_t _period_us;
+    int _period_us;
 };
 
 #endif
\ No newline at end of file
diff -r e4ac7c1a14de -r 0670023d3f36 Microduino_Protocol_HardSer.cpp
--- a/Microduino_Protocol_HardSer.cpp	Fri May 27 01:44:31 2016 +0000
+++ b/Microduino_Protocol_HardSer.cpp	Sat May 28 05:09:18 2016 +0000
@@ -1,5 +1,7 @@
 #include "Microduino_Protocol_HardSer.h"
 
+//Timer _timer;
+extern Timer g_cubeTimer;
 uint8_t getChecksum(uint8_t length, uint8_t cmd, uint8_t mydata[])
 {
     //三个参数分别为: 数据长度  ,  指令代码  ,  实际数据数组
@@ -10,7 +12,6 @@
     return checksum;
 }
 
-
 /* Protocol::Protocol(PRO_PORT *ser , byte _channel) {
   //  common_init();  // Set everything to common state, then...
   this->channel = _channel;
@@ -20,16 +21,15 @@
   P_Serial = ser; // ...override P_Serial with value passed.
   } */
 
-
 void Protocol::begin(uint16_t _baud)
 {
+    //_timer.start();
     //P_Serial->begin(_baud);
     P_Serial->baud(_baud);
     //delay(20);
-    wait_ms(20);
+    //wait_ms(20);
 }
 
-
 bool Protocol::available(bool _sta)
 {
     //if (P_Serial->available() > 0) {
@@ -52,12 +52,12 @@
     return false;
 }
 
-
 uint8_t Protocol::parse(uint16_t* _data, bool _mod)
 {
     if (available(!_mod)) {
         //time = millis();
-        time = _timer.read_ms();
+        //time = _timer.read_ms();
+        time = g_cubeTimer.read_ms();
         do {
             if (this->sta) {
                 this->sta = false;
@@ -97,7 +97,7 @@
             } else if (!_mod) {
                 return P_BUSY;
             }
-        } while (_mod && (available(true) && _timer.read_ms() - time < 100));
+        } while (_mod && (available(true) && g_cubeTimer.read_ms() - time < 100));
 
         if (_mod) {
             return P_TIMEOUT;
diff -r e4ac7c1a14de -r 0670023d3f36 Microduino_Protocol_HardSer.h
--- a/Microduino_Protocol_HardSer.h	Fri May 27 01:44:31 2016 +0000
+++ b/Microduino_Protocol_HardSer.h	Sat May 28 05:09:18 2016 +0000
@@ -22,14 +22,14 @@
 
 class Protocol {
   public:
-    Protocol(PRO_PORT *ser , uint8_t _channel) : _timer(),num(0),time(0),sta(false),error(false){ // Constructor when using HardwareSerial
+    Protocol(PRO_PORT *ser , uint8_t _channel) : num(0),time(0),sta(false),error(false){ // Constructor when using HardwareSerial
       //  common_init();  // Set everything to common state, then...
       channel = _channel;
       num = 0;
       sta = false;
       error = false;
       P_Serial = ser; // ...override P_Serial with value passed.
-      _timer.start();
+      //_timer.start();
     }
     void begin(uint16_t _baud);
     uint8_t parse(uint16_t* _data, bool _mod);
@@ -46,7 +46,7 @@
     bool available(bool _sta);
     PRO_PORT *P_Serial;
     
-    Timer _timer;
+    
 };
 
 
diff -r e4ac7c1a14de -r 0670023d3f36 Protocol.h
--- a/Protocol.h	Fri May 27 01:44:31 2016 +0000
+++ b/Protocol.h	Sat May 28 05:09:18 2016 +0000
@@ -2,6 +2,7 @@
 
 //BLE//////////////////////
 Serial pc(P0_4,P0_0);
+//Serial pc(P0_0, P0_4);
 Protocol bleProtocol(&pc, TYPE_NUM);  //软串口,校验数据类
 
 #define this_node  1  //设置本机ID
diff -r e4ac7c1a14de -r 0670023d3f36 main.cpp
--- a/main.cpp	Fri May 27 01:44:31 2016 +0000
+++ b/main.cpp	Sat May 28 05:09:18 2016 +0000
@@ -1,10 +1,12 @@
 #include "mbed.h"
-#include "rtos.h"
+//#include "rtos.h"
 #include "MicroduinoPinNames.h"
 #include "userDef.h"
 #include "Protocol.h"
 #include "Microduino_Motor.h"
 
+Timer g_cubeTimer;
+#if 1
 Motor MotorLeft(motor_pin0A, motor_pin0B);
 Motor MotorRight(motor_pin1A, motor_pin1B);
 ///////////////////////////////////////////////////////////
@@ -13,10 +15,8 @@
 bool mode = 0; //nrf或者ble模式
 int16_t throttle = 0; //油门
 int16_t steering = 0; //转向
-unsigned long safe_ms;
+int safe_ms = 0;
 
-DigitalOut myled(D11);
-Timer g_cubeTimer;
 //Serial pc(P0_4,P0_0);
 
 static long map(long x, long in_min, long in_max, long out_min, long out_max)
@@ -26,6 +26,7 @@
 
 int main()
 {
+    bool freeFlag = true;
     g_cubeTimer.start();
     mode = protocolSetup();  //遥控接收器初始化
 
@@ -41,6 +42,7 @@
             MotorRight.Driver(MotorRight.GetData(throttle, steering, CHAN_RIGHT));
 
 #ifdef _DEBUG
+asdf
             Serial.print("DATA OK :[");
             for (int a = 0; a < CHANNEL_NUM; a++) {
                 Serial.print(channalData[a]);
@@ -53,7 +55,7 @@
 #endif
             safe_ms = g_cubeTimer.read_ms();
         }
-
+#if 0
         if (safe_ms > g_cubeTimer.read_ms()) {
             safe_ms = g_cubeTimer.read_ms();
         }
@@ -63,7 +65,36 @@
             //MotorLeft.Brake();
             //MotorRight.Brake();
         }
+#endif
         //pc.printf("Hello world\r\n");
         //sleep();
     }
 }
+#else
+DigitalOut myled(D13);
+PwmOut PWM_A(motor_pin0A);
+PwmOut PWM_B(motor_pin0B);
+int pv = 0;
+int main()
+{
+    myled.write(1);
+    PWM_A.period_us(255);
+    PWM_B.period_us(255);
+    
+    PWM_A.pulsewidth_us(200);
+    PWM_B.pulsewidth_us(0);
+    while (1)
+    {
+        #if 0
+        PWM_B.pulsewidth_us(pv);
+        pv++;
+        #endif
+        wait(0.5);
+        myled = !myled;
+        if (pv >= 255)
+        {
+            pv = 0;
+        }
+    }
+}
+#endif
\ No newline at end of file
diff -r e4ac7c1a14de -r 0670023d3f36 userDef.h
--- a/userDef.h	Fri May 27 01:44:31 2016 +0000
+++ b/userDef.h	Sat May 28 05:09:18 2016 +0000
@@ -30,10 +30,26 @@
 #define motor_fixL 1  //速度修正 -1到1之间
 #define motor_fixR 1  //速度修正 -1到1之间
 #else
+#if 0
 #define motor_pin0A D6  //PWM
 #define motor_pin0B D8
 #define motor_pin1A D5  //PWM
 #define motor_pin1B D7
 #define motor_fixL -1 //速度修正 -1到1之间
 #define motor_fixR -1 //速度修正 -1到1之间
+#elif 1
+#define motor_pin0A D8  //PWM
+#define motor_pin0B D6
+#define motor_pin1A D7  //PWM 
+#define motor_pin1B D5
+#define motor_fixL 1  //速度修正 -1到1之间
+#define motor_fixR 1  //速度修正 -1到1之间
+#else
+#define motor_pin0A D8  //PWM
+#define motor_pin0B D6
+#define motor_pin1A D7  //PWM
+#define motor_pin1B D5
+#define motor_fixL -1 //速度修正 -1到1之间
+#define motor_fixR -1 //速度修正 -1到1之间
 #endif
+#endif