Microduino的cube小车。

Dependencies:   mbed-rtos mbed

Committer:
lixianyu
Date:
Wed May 25 11:52:03 2016 +0000
Revision:
1:758ccab13947
Child:
2:70ca3e685cca
??????

Who changed what in which revision?

UserRevisionLine numberNew contents of line
lixianyu 1:758ccab13947 1 #include "Microduino_Motor.h"
lixianyu 1:758ccab13947 2
lixianyu 1:758ccab13947 3 static motor_t motors[10]; // static array of key structures
lixianyu 1:758ccab13947 4
lixianyu 1:758ccab13947 5 uint8_t MotorCount = 0; // the total number of attached keys
lixianyu 1:758ccab13947 6
lixianyu 1:758ccab13947 7 Motor::Motor(uint8_t _motor_pinA, uint8_t _motor_pinB)
lixianyu 1:758ccab13947 8 {
lixianyu 1:758ccab13947 9 if ( MotorCount < 10) {
lixianyu 1:758ccab13947 10 this->motorIndex = MotorCount++; // assign a key index to this instance
lixianyu 1:758ccab13947 11 if (_motor_pinA < NUM_DIGITAL_PINS && _motor_pinB < NUM_DIGITAL_PINS) {
lixianyu 1:758ccab13947 12 pinMode( _motor_pinA, OUTPUT) ;
lixianyu 1:758ccab13947 13 motors[this->motorIndex].Pin.nbr_A = _motor_pinA;
lixianyu 1:758ccab13947 14
lixianyu 1:758ccab13947 15 pinMode( _motor_pinB, OUTPUT) ;
lixianyu 1:758ccab13947 16 motors[this->motorIndex].Pin.nbr_B = _motor_pinB;
lixianyu 1:758ccab13947 17
lixianyu 1:758ccab13947 18 this->fix=1;
lixianyu 1:758ccab13947 19 }
lixianyu 1:758ccab13947 20 } else
lixianyu 1:758ccab13947 21 this->motorIndex = 255 ; // too many keys
lixianyu 1:758ccab13947 22 }
lixianyu 1:758ccab13947 23
lixianyu 1:758ccab13947 24 void Motor::Fix(float _fix)
lixianyu 1:758ccab13947 25 {
lixianyu 1:758ccab13947 26 this->fix=_fix;
lixianyu 1:758ccab13947 27 }
lixianyu 1:758ccab13947 28
lixianyu 1:758ccab13947 29 int16_t Motor::GetData(int16_t _throttle, int16_t _steering, bool _dir)
lixianyu 1:758ccab13947 30 {
lixianyu 1:758ccab13947 31 this->_motor_vol = _throttle;
lixianyu 1:758ccab13947 32
lixianyu 1:758ccab13947 33 if(_dir)
lixianyu 1:758ccab13947 34 this->_motor_vol -= _steering / 2;
lixianyu 1:758ccab13947 35 else
lixianyu 1:758ccab13947 36 this->_motor_vol += _steering / 2;
lixianyu 1:758ccab13947 37
lixianyu 1:758ccab13947 38 if (this->_motor_vol > 255)
lixianyu 1:758ccab13947 39 this->_motor_vol = 255;
lixianyu 1:758ccab13947 40 else if (this->_motor_vol < -255)
lixianyu 1:758ccab13947 41 this->_motor_vol = -255;
lixianyu 1:758ccab13947 42
lixianyu 1:758ccab13947 43 this->_motor_vol *= fix;
lixianyu 1:758ccab13947 44
lixianyu 1:758ccab13947 45 return this->_motor_vol;
lixianyu 1:758ccab13947 46 }
lixianyu 1:758ccab13947 47
lixianyu 1:758ccab13947 48
lixianyu 1:758ccab13947 49 void Motor::Driver(int16_t _motor_driver)
lixianyu 1:758ccab13947 50 {
lixianyu 1:758ccab13947 51 int8_t channel_A = motors[this->motorIndex].Pin.nbr_A;
lixianyu 1:758ccab13947 52 int8_t channel_B = motors[this->motorIndex].Pin.nbr_B;
lixianyu 1:758ccab13947 53 if (_motor_driver == 0) {
lixianyu 1:758ccab13947 54 digitalWrite(channel_A, LOW);
lixianyu 1:758ccab13947 55 digitalWrite(channel_B, LOW);
lixianyu 1:758ccab13947 56 } else if (_motor_driver > 0) {
lixianyu 1:758ccab13947 57 analogWrite(channel_A, _motor_driver);
lixianyu 1:758ccab13947 58 digitalWrite(channel_B, LOW);
lixianyu 1:758ccab13947 59 } else {
lixianyu 1:758ccab13947 60 analogWrite(channel_A, 255 + _motor_driver);
lixianyu 1:758ccab13947 61 digitalWrite(channel_B, HIGH);
lixianyu 1:758ccab13947 62 }
lixianyu 1:758ccab13947 63 }
lixianyu 1:758ccab13947 64
lixianyu 1:758ccab13947 65 void Motor::Free()
lixianyu 1:758ccab13947 66 {
lixianyu 1:758ccab13947 67 int8_t channel_A = motors[this->motorIndex].Pin.nbr_A;
lixianyu 1:758ccab13947 68 int8_t channel_B = motors[this->motorIndex].Pin.nbr_B;
lixianyu 1:758ccab13947 69 digitalWrite(channel_A, LOW);
lixianyu 1:758ccab13947 70 digitalWrite(channel_B, LOW);
lixianyu 1:758ccab13947 71 }
lixianyu 1:758ccab13947 72
lixianyu 1:758ccab13947 73 void Motor::Brake()
lixianyu 1:758ccab13947 74 {
lixianyu 1:758ccab13947 75 int8_t channel_A = motors[this->motorIndex].Pin.nbr_A;
lixianyu 1:758ccab13947 76 int8_t channel_B = motors[this->motorIndex].Pin.nbr_B;
lixianyu 1:758ccab13947 77 digitalWrite(channel_A, HIGH);
lixianyu 1:758ccab13947 78 digitalWrite(channel_B, HIGH);
lixianyu 1:758ccab13947 79 }