test

Dependencies:   mbed

Fork of CubeFine by Li Weiyi

Files at this revision

API Documentation at this revision

Comitter:
beian10
Date:
Mon Jul 04 07:17:39 2016 +0000
Parent:
1:54a2d380f8c7
Commit message:
V2

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
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
diff -r 54a2d380f8c7 -r 7964622fb5a5 Microduino_Motor.cpp
--- a/Microduino_Motor.cpp	Fri Jul 01 09:41:15 2016 +0000
+++ b/Microduino_Motor.cpp	Mon Jul 04 07:17:39 2016 +0000
@@ -1,34 +1,16 @@
 #include "Microduino_Motor.h"
 
-static motor_t motors[10];                          // static array of key structures
-
-uint8_t MotorCount = 0;                                     // the total number of attached keys
-
 Motor::Motor(PinName _motor_pinA, PinName _motor_pinB)
 {
-    if ( MotorCount < 10) {
-        this->motorIndex = MotorCount++;                    // assign a key index to this instance
-        //if (_motor_pinA < NUM_DIGITAL_PINS && _motor_pinB < NUM_DIGITAL_PINS) {
-        if (true) {
-
             _period_us = 255; // 500Hz
             pwmout_init(&_pwmA, _motor_pinA);
             pwmout_period_us(&_pwmA, _period_us); // 500Hz
-            pwmout_pulsewidth_us(&_pwmA, 1);
-
-            motors[this->motorIndex].Pin.nbr_A = _motor_pinA;
+            pwmout_pulsewidth_us(&_pwmA, 0);
 
-            pwmout_init(&_pwmB, _motor_pinB);
-            pwmout_period_us(&_pwmB, _period_us); // 500Hz
-            pwmout_pulsewidth_us(&_pwmB, 1);
 
-            motors[this->motorIndex].Pin.nbr_B = _motor_pinB;
+            gpio_init_out(&gpioB, _motor_pinB);
 
             this->fix=1;
-        }
-    } else {
-        this->motorIndex = 255 ;  // too many keys
-    }
 }
 
 void Motor::Fix(float _fix)
@@ -53,102 +35,38 @@
     else if (this->_motor_vol < -255)
         this->_motor_vol = -255;
 
-    //this->_motor_vol *= fix;
+    this->_motor_vol *= fix;
 
     return this->_motor_vol;
 }
 
-#if 0
-void Motor::Driver(int16_t _motor_driver)
-{
-    int8_t channel_A = motors[this->motorIndex].Pin.nbr_A;
-    int8_t channel_B = motors[this->motorIndex].Pin.nbr_B;
-    if (_motor_driver == 0)   {
-        digitalWrite(channel_A, LOW);
-        digitalWrite(channel_B, LOW);
-    } else if (_motor_driver > 0)   {
-        analogWrite(channel_A, _motor_driver);
-        digitalWrite(channel_B, LOW);
-    } else  {
-        analogWrite(channel_A, 255 + _motor_driver);
-        digitalWrite(channel_B, HIGH);
-    }
-}
-#else
 void Motor::Driver(int16_t _motor_driver)
 {
-    //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);
+        gpio_write(&gpioB, 0);
     } else if (_motor_driver > 0) {
-        #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
+        gpio_write(&gpioB, 0);
     } else {
-        #if 0
-        _motor_driver = 255 + _motor_driver;
-        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
+        //_motor_driver = abs(_motor_driver);
+        pulseWidth = _period_us / 255 * (255 + _motor_driver);
+        pwmout_pulsewidth_us(&_pwmA, pulseWidth);
+        gpio_write(&gpioB, 1);
     }
 }
-#endif
 
 void Motor::Free()
 {
-    int8_t channel_A = motors[this->motorIndex].Pin.nbr_A;
-    int8_t channel_B = motors[this->motorIndex].Pin.nbr_B;
-#if 0
-    digitalWrite(channel_A, LOW);
-    digitalWrite(channel_B, LOW);
-#else
     pwmout_pulsewidth_us(&_pwmA, 0);
-    pwmout_pulsewidth_us(&_pwmB, 0);
-#endif
+    gpio_write(&gpioB, 0);
 }
 
 void Motor::Brake()
 {
-    int8_t channel_A = motors[this->motorIndex].Pin.nbr_A;
-    int8_t channel_B = motors[this->motorIndex].Pin.nbr_B;
-#if 0
-    digitalWrite(channel_A, HIGH);
-    digitalWrite(channel_B, HIGH);
-#else
     pwmout_pulsewidth_us(&_pwmA, _period_us);
-    pwmout_pulsewidth_us(&_pwmB, _period_us);
-#endif
+    gpio_write(&gpioB, 1);
 }
\ No newline at end of file
diff -r 54a2d380f8c7 -r 7964622fb5a5 Microduino_Motor.h
--- a/Microduino_Motor.h	Fri Jul 01 09:41:15 2016 +0000
+++ b/Microduino_Motor.h	Mon Jul 04 07:17:39 2016 +0000
@@ -1,24 +1,16 @@
 #ifndef Motor_h
 #define Motor_h
 
-//#include "Arduino.h"
 #include "mbed.h"
 
 #define CHAN_LEFT 0
 #define CHAN_RIGHT 1
 
-#if 0
-typedef struct  {
-    uint8_t nbr_A        :6 ;
-    uint8_t nbr_B        :6 ;
-} MotorPin_t;
-#else
 typedef struct  {
     PinName nbr_A;
     PinName nbr_B;
 } MotorPin_t;
 
-#endif
 
 typedef struct {
     MotorPin_t Pin;
@@ -34,12 +26,12 @@
     void Brake();
     int16_t GetData(int16_t _throttle, int16_t _steering, uint8_t _dir);
 private:
-    uint8_t motorIndex;               // index into the channel data for this key
+//    uint8_t motorIndex;               // index into the channel data for this key
     float fix;
     int16_t _motor_vol;
 protected:
     pwmout_t _pwmA;
-    pwmout_t _pwmB;
+    gpio_t gpioB;
     int _period_us;
 };
 
diff -r 54a2d380f8c7 -r 7964622fb5a5 Microduino_Protocol_HardSer.cpp
--- a/Microduino_Protocol_HardSer.cpp	Fri Jul 01 09:41:15 2016 +0000
+++ b/Microduino_Protocol_HardSer.cpp	Mon Jul 04 07:17:39 2016 +0000
@@ -2,7 +2,7 @@
 #include "MicroduinoPinNames.h"
 //Timer _timer;
 extern Timer g_cubeTimer;
-//DigitalOut myled(D13);
+
 uint8_t getChecksum(uint8_t length, uint8_t cmd, uint8_t mydata[])
 {
     //三个参数分别为: 数据长度  ,  指令代码  ,  实际数据数组
@@ -13,27 +13,10 @@
     return checksum;
 }
 
-/* Protocol::Protocol(PRO_PORT *ser , byte _channel) {
-  //  common_init();  // Set everything to common state, then...
-  this->channel = _channel;
-  this->num = 0;
-  this->sta = false;
-  this->error = false;
-  P_Serial = ser; // ...override P_Serial with value passed.
-  } */
-static void uart_callback(void)
-{
-    //myled = !myled;
-}
+
 void Protocol::begin(uint16_t _baud)
 {
-    //myled = 0;
-    //_timer.start();
-    //P_Serial->begin(_baud);
     P_Serial->baud(_baud);
-    //P_Serial->attach(uart_callback, Serial::RxIrq);
-    //delay(20);
-    //wait_ms(20);
 }
 
 bool Protocol::available(bool _sta)
@@ -108,7 +91,8 @@
         if (_mod) {
             return P_TIMEOUT;
         }
-    } else {
-        return P_NONE;
     }
+    
+    return P_NONE;
+    
 }
\ No newline at end of file
diff -r 54a2d380f8c7 -r 7964622fb5a5 Protocol.h
--- a/Protocol.h	Fri Jul 01 09:41:15 2016 +0000
+++ b/Protocol.h	Mon Jul 04 07:17:39 2016 +0000
@@ -1,7 +1,7 @@
 #include "Microduino_Protocol_HardSer.h"
 
 //BLE//////////////////////
-Serial pc(D1, D0);
+Serial pc(D3, D2);
 
 Protocol bleProtocol(&pc, TYPE_NUM);  //软串口,校验数据类
 
@@ -35,16 +35,10 @@
         case P_FINE:  //DATA OK
             return true;
         case P_ERROR: //DATA ERROR
-#ifdef BLE_SoftSerial
-            mySerial.stopListening();
-            mySerial.listen();
-#endif
+
             break;
         case P_TIMEOUT: //DATA TIMEOUT
-#ifdef BLE_SoftSerial
-            mySerial.stopListening();
-            mySerial.listen();
-#endif
+
             break;
     }
     return false;
diff -r 54a2d380f8c7 -r 7964622fb5a5 main.cpp
--- a/main.cpp	Fri Jul 01 09:41:15 2016 +0000
+++ b/main.cpp	Mon Jul 04 07:17:39 2016 +0000
@@ -1,15 +1,13 @@
 #include "mbed.h"
-//#include "rtos.h"
 #include "MicroduinoPinNames.h"
 #include "userDef.h"
 #include "Protocol.h"
 #include "Microduino_Motor.h"
 
-DigitalOut led_red(D5);
 
 Timer g_cubeTimer;
 //Timeout g_cubeTimeout;
-#if 1
+
 Motor MotorLeft(motor_pin0A, motor_pin0B);
 Motor MotorRight(motor_pin1A, motor_pin1B);
 ///////////////////////////////////////////////////////////
@@ -19,43 +17,22 @@
 int16_t throttle = 0; //油门
 int16_t steering = 0; //转向
 int safe_ms = 0;
-DigitalOut myled(D13);
-InterruptIn wkp(D0);
-InterruptIn wkp1(D1);
+
 static long map(long x, long in_min, long in_max, long out_min, long out_max)
 {
     return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
 }
 
-/*
-static void wake_up(void)
-{
-    //myled = 0;
-}
-*/
-
 int main()
 {
-#if 0// To test wake up from deepsleep(), failed....but wake up from sleep() work. sleep() will reduce 2mA.
-    wkp.fall(wake_up);
-    wkp.rise(&wake_up);
-    wkp1.fall(&wake_up);
-    wkp1.rise(&wake_up);
-#endif
-    led_red = 0;
-    //myled = 1;
-    //g_cubeTimer.start();
+
+    g_cubeTimer.start();
 
     mode = protocolSetup();  //遥控接收器初始化
 
     MotorLeft.Fix(motor_fixL);
     MotorRight.Fix(motor_fixR);
-    
-    MotorLeft.Driver(255);
-    MotorRight.Driver(255);
-    
-    wait(0.5);
-    //mypc.baud(115200);
+
     
     while (1) {
         
@@ -75,36 +52,7 @@
         if (g_cubeTimer.read_ms() - safe_ms > SAFE_TIME_OUT) {
             MotorLeft.Free();
             MotorRight.Free();
-            //sleep();//待机待机电流可减少4mA左右
-            //deepsleep();
         }
         
     } // while
-}
-
-#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
+}
\ No newline at end of file