work fine.

Dependencies:   mbed

Files at this revision

API Documentation at this revision

Comitter:
lixianyu
Date:
Thu Jun 02 04:03:31 2016 +0000
Commit message:
work fine.

Changed in this revision

MicroduinoPinNames.h Show annotated file Show diff for this revision Revisions of this file
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
mbed.bld 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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/MicroduinoPinNames.h	Thu Jun 02 04:03:31 2016 +0000
@@ -0,0 +1,25 @@
+
+#define D0  P0_0
+#define D1  P0_4
+#define D2  P0_28
+#define D3  P0_26
+#define D4  P0_25
+#define D5  P0_24
+#define D6  P0_1
+#define D7  P0_20
+#define D8  P0_19
+#define D9  P0_18
+#define D10 P0_17
+#define D11 P0_16
+#define D12 P0_15
+#define D13 P0_13
+
+#define A0  P0_7
+#define A1  P0_6
+#define A2  P0_14
+#define A3  P0_23
+#define A6  P0_22
+#define A7  P0_21
+
+#define  SCL P0_10
+#define  SDA P0_11
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Microduino_Motor.cpp	Thu Jun 02 04:03:31 2016 +0000
@@ -0,0 +1,159 @@
+#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) {
+#if 0
+            pinMode( _motor_pinA, OUTPUT) ;
+#else
+            _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;
+
+#if 0
+            pinMode( _motor_pinB, OUTPUT) ;
+#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;
+
+            this->fix=1;
+        }
+    } else {
+        this->motorIndex = 255 ;  // too many keys
+    }
+}
+
+void Motor::Fix(float _fix)
+{
+    this->fix=_fix;
+}
+
+int16_t Motor::GetData(int16_t _throttle, int16_t _steering, uint8_t _dir)
+{
+    this->_motor_vol = _throttle;
+
+    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;
+
+    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);
+    } 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
+    } 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
+    }
+}
+#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
+}
+
+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
+}
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Microduino_Motor.h	Thu Jun 02 04:03:31 2016 +0000
@@ -0,0 +1,46 @@
+#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;
+} motor_t;
+
+class Motor
+{
+public:
+    Motor(PinName _motor_pinA, PinName _motor_pinB);
+    void Fix(float _fix);
+    void Driver(int16_t _motor_driver);
+    void Free();
+    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
+    float fix;
+    int16_t _motor_vol;
+protected:
+    pwmout_t _pwmA;
+    pwmout_t _pwmB;
+    int _period_us;
+};
+
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Microduino_Protocol_HardSer.cpp	Thu Jun 02 04:03:31 2016 +0000
@@ -0,0 +1,114 @@
+#include "Microduino_Protocol_HardSer.h"
+#include "MicroduinoPinNames.h"
+//Timer _timer;
+extern Timer g_cubeTimer;
+//DigitalOut myled(D13);
+uint8_t getChecksum(uint8_t length, uint8_t cmd, uint8_t mydata[])
+{
+    //三个参数分别为: 数据长度  ,  指令代码  ,  实际数据数组
+    uint8_t checksum = 0;
+    checksum ^= (length & 0xFF);
+    checksum ^= (cmd & 0xFF);
+    for (int i = 0; i < length; i++) checksum ^= (mydata[i] & 0xFF);
+    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)
+{
+    //if (P_Serial->available() > 0) {
+    if (P_Serial->readable() > 0) {
+        if (_sta) {
+            this->inCache = this->inChar;
+            //this->inChar = P_Serial->read();
+            this->inChar = P_Serial->getc();
+            this->buffer[num] = this->inChar;
+
+            if (this->num > BUFFER_MAX - 1) {
+                this->num = 0;
+                return false;
+            } else {
+                this->num++;
+            }
+        }
+        return true;
+    }
+    return false;
+}
+
+uint8_t Protocol::parse(uint16_t* _data, bool _mod)
+{
+    if (available(!_mod)) {
+        //time = millis();
+        //time = _timer.read_ms();
+        time = g_cubeTimer.read_ms();
+        do {
+            if (this->sta) {
+                this->sta = false;
+                this->num = 0;
+                if (this->inChar == this->channel) {
+                    this->error = false;
+                    if (!_mod) {
+                        return P_BUSY;
+                    }
+                } else  {
+                    this->error = true;
+                    return P_ERROR;
+                }
+            }
+
+            if (this->inChar == 0xBB && this->inCache == 0xAA) {
+                this->sta = true;
+                if (!_mod) {
+                    return P_BUSY;
+                }
+            }
+
+            if (this->num  == (CHANNEL_NUM * 2 + 1) && !this->error) {
+                this->inCache = this->buffer[CHANNEL_NUM * 2];
+                this->buffer[CHANNEL_NUM * 2] = NULL;
+                this->inChar = getChecksum(CHANNEL_NUM * 2, 200, this->buffer);
+
+                this->num = 0;
+                if (!this->error && this->inCache == this->inChar) {
+                    for (uint8_t a = 0; a < CHANNEL_NUM; a++) {
+                        _data[a] = ((uint16_t)(this->buffer[a * 2])) | ((uint16_t)this->buffer[a * 2 + 1] << 8);
+                    }
+                    return P_FINE;
+                } else {
+                    return P_ERROR;
+                }
+            } else if (!_mod) {
+                return P_BUSY;
+            }
+        } while (_mod && (available(true) && g_cubeTimer.read_ms() - time < 100));
+
+        if (_mod) {
+            return P_TIMEOUT;
+        }
+    } else {
+        return P_NONE;
+    }
+}
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Microduino_Protocol_HardSer.h	Thu Jun 02 04:03:31 2016 +0000
@@ -0,0 +1,53 @@
+#ifndef _MICRODUINO_PROTOCOL_HARDSER_H
+#define _MICRODUINO_PROTOCOL_HARDSER_H
+
+#include "mbed.h"
+
+#define PRO_PORT Serial
+
+enum p_sta {
+    P_ERROR,
+    P_BUSY,
+    P_NONE,
+    P_FINE,
+    P_TIMEOUT,
+};
+
+#define MODE_WHILE 1
+#define MODE_LOOP 0
+
+#define BUFFER_MAX 256
+#define CHANNEL_NUM 8
+#define TYPE_NUM 0xC8
+
+class Protocol {
+  public:
+    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();
+    }
+    void begin(uint16_t _baud);
+    uint8_t parse(uint16_t* _data, bool _mod);
+
+  private:
+    uint8_t inChar, inCache;
+    uint8_t buffer[BUFFER_MAX];
+    uint8_t channel;
+    uint32_t num ;
+    uint32_t time;
+    bool sta;
+    bool error;
+
+    bool available(bool _sta);
+    PRO_PORT *P_Serial;
+    
+    
+};
+
+
+#endif
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/Protocol.h	Thu Jun 02 04:03:31 2016 +0000
@@ -0,0 +1,52 @@
+#include "Microduino_Protocol_HardSer.h"
+
+//BLE//////////////////////
+Serial pc(P0_4,P0_0);
+//Serial pc(P0_0, P0_4);
+Protocol bleProtocol(&pc, TYPE_NUM);  //软串口,校验数据类
+
+#define this_node  1  //设置本机ID
+#define other_node 0
+struct send_a { //发送
+    uint32_t node_ms;   //节点运行时间
+};
+struct receive_a { //接收
+    uint32_t ms;
+    uint16_t rf_CH[CHANNEL_NUM];
+};
+
+//Mode//////////////////////
+enum _Mode {
+    NRF,
+    BLE
+};
+
+bool protocolSetup(void)
+{
+    bleProtocol.begin(BLE_SPEED);
+    return BLE;
+}
+
+bool protocolRead(uint16_t *_channel, bool _mode)
+{
+    switch (bleProtocol.parse(_channel, MODE_WHILE)) {
+        case P_NONE:  //DATA NONE
+            break;
+        case P_FINE:  //DATA OK
+            return true;
+            break;
+        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;
+}
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main.cpp	Thu Jun 02 04:03:31 2016 +0000
@@ -0,0 +1,107 @@
+#include "mbed.h"
+//#include "rtos.h"
+#include "MicroduinoPinNames.h"
+#include "userDef.h"
+#include "Protocol.h"
+#include "Microduino_Motor.h"
+
+Timer g_cubeTimer;
+Timeout g_cubeTimeout;
+#if 1
+Motor MotorLeft(motor_pin0A, motor_pin0B);
+Motor MotorRight(motor_pin1A, motor_pin1B);
+///////////////////////////////////////////////////////////
+#define CHANNEL_NUM 8
+uint16_t channalData[CHANNEL_NUM]; //8通道数据
+bool mode = 0; //nrf或者ble模式
+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 1// 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
+    //myled = 1;
+    g_cubeTimer.start();
+
+    mode = protocolSetup();  //遥控接收器初始化
+
+    MotorLeft.Fix(motor_fixL);
+    MotorRight.Fix(motor_fixR);
+    //mypc.baud(115200);
+    while (1) {
+        if (protocolRead(channalData, mode)) { //判断是否接收到遥控信号
+            throttle = map(channalData[CHANNEL_THROTTLE], 1000, 2000, -MAX_THROTTLE, MAX_THROTTLE);
+            steering = map(channalData[CHANNEL_STEERING], 1000, 2000, -MAX_STEERING, MAX_STEERING);
+
+            MotorLeft.Driver(MotorLeft.GetData(throttle, steering, CHAN_LEFT));
+            MotorRight.Driver(MotorRight.GetData(throttle, steering, CHAN_RIGHT));
+
+#ifdef _DEBUG
+            Serial.print("DATA OK :[");
+            for (int a = 0; a < CHANNEL_NUM; a++) {
+                Serial.print(channalData[a]);
+                Serial.print(" ");
+            }
+            Serial.print("],throttle:");
+            Serial.print(throttle);
+            Serial.print(",steering:");
+            Serial.println(steering);
+#endif
+            safe_ms = g_cubeTimer.read_ms();
+        }
+
+        if (safe_ms > g_cubeTimer.read_ms()) {
+            safe_ms = g_cubeTimer.read_ms();
+        }
+        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
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed.bld	Thu Jun 02 04:03:31 2016 +0000
@@ -0,0 +1,1 @@
+http://mbed.org/users/mbed_official/code/mbed/builds/6c34061e7c34
\ No newline at end of file
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/userDef.h	Thu Jun 02 04:03:31 2016 +0000
@@ -0,0 +1,55 @@
+//#include <arduino.h>
+#include "MicroduinoPinNames.h"
+//#define _DEBUG  //DEBUG调试
+
+#if 0
+//#define BLE_SoftSerial  //软串口模式
+#ifndef BLE_SoftSerial  //如果没开启软串口,就开硬串口模式
+#if defined(__AVR_ATmega32U4__)
+#define BLE_HardSerial Serial1
+#else
+#define BLE_HardSerial Serial
+#endif
+#endif
+#endif
+
+#define BLE_SPEED 9600  //蓝牙接口速度
+#define NRF_CHANNEL 70  //nRF通道
+
+#define SAFE_TIME_OUT 250   //失控保护时间
+#define MAX_THROTTLE 255 //最大油门 < 255
+#define MAX_STEERING 512 //最大转向 < 512
+#define CHANNEL_THROTTLE  1 //油门通道
+#define CHANNEL_STEERING  0 //转向通道
+
+#if defined(__AVR_ATmega32U4__) || (__AVR_ATmega1284P__) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega128RFA1__)
+#define motor_pin0A 8  //PWM
+#define motor_pin0B 6
+#define motor_pin1A 7  //PWM 
+#define motor_pin1B 5
+#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