Li Weiyi
/
Cube
Microduino的cube小车。
Microduino_Motor.cpp@2:70ca3e685cca, 2016-05-25 (annotated)
- Committer:
- lixianyu
- Date:
- Wed May 25 13:25:09 2016 +0000
- Revision:
- 2:70ca3e685cca
- Parent:
- 1:758ccab13947
- Child:
- 3:e4ac7c1a14de
???????????
Who changed what in which revision?
User | Revision | Line number | New 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 | 2:70ca3e685cca | 7 | Motor::Motor(PinName _motor_pinA, PinName _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 | 2:70ca3e685cca | 11 | //if (_motor_pinA < NUM_DIGITAL_PINS && _motor_pinB < NUM_DIGITAL_PINS) { |
lixianyu | 2:70ca3e685cca | 12 | if (true) { |
lixianyu | 2:70ca3e685cca | 13 | //pinMode( _motor_pinA, OUTPUT) ; |
lixianyu | 2:70ca3e685cca | 14 | gpio_init_out(&gpioA, _motor_pinA); |
lixianyu | 1:758ccab13947 | 15 | motors[this->motorIndex].Pin.nbr_A = _motor_pinA; |
lixianyu | 1:758ccab13947 | 16 | |
lixianyu | 2:70ca3e685cca | 17 | //pinMode( _motor_pinB, OUTPUT) ; |
lixianyu | 2:70ca3e685cca | 18 | gpio_init_out(&gpioB, _motor_pinB); |
lixianyu | 1:758ccab13947 | 19 | motors[this->motorIndex].Pin.nbr_B = _motor_pinB; |
lixianyu | 1:758ccab13947 | 20 | |
lixianyu | 1:758ccab13947 | 21 | this->fix=1; |
lixianyu | 1:758ccab13947 | 22 | } |
lixianyu | 1:758ccab13947 | 23 | } else |
lixianyu | 1:758ccab13947 | 24 | this->motorIndex = 255 ; // too many keys |
lixianyu | 1:758ccab13947 | 25 | } |
lixianyu | 1:758ccab13947 | 26 | |
lixianyu | 1:758ccab13947 | 27 | void Motor::Fix(float _fix) |
lixianyu | 1:758ccab13947 | 28 | { |
lixianyu | 1:758ccab13947 | 29 | this->fix=_fix; |
lixianyu | 1:758ccab13947 | 30 | } |
lixianyu | 1:758ccab13947 | 31 | |
lixianyu | 1:758ccab13947 | 32 | int16_t Motor::GetData(int16_t _throttle, int16_t _steering, bool _dir) |
lixianyu | 1:758ccab13947 | 33 | { |
lixianyu | 1:758ccab13947 | 34 | this->_motor_vol = _throttle; |
lixianyu | 1:758ccab13947 | 35 | |
lixianyu | 1:758ccab13947 | 36 | if(_dir) |
lixianyu | 1:758ccab13947 | 37 | this->_motor_vol -= _steering / 2; |
lixianyu | 1:758ccab13947 | 38 | else |
lixianyu | 1:758ccab13947 | 39 | this->_motor_vol += _steering / 2; |
lixianyu | 1:758ccab13947 | 40 | |
lixianyu | 1:758ccab13947 | 41 | if (this->_motor_vol > 255) |
lixianyu | 1:758ccab13947 | 42 | this->_motor_vol = 255; |
lixianyu | 1:758ccab13947 | 43 | else if (this->_motor_vol < -255) |
lixianyu | 1:758ccab13947 | 44 | this->_motor_vol = -255; |
lixianyu | 1:758ccab13947 | 45 | |
lixianyu | 1:758ccab13947 | 46 | this->_motor_vol *= fix; |
lixianyu | 1:758ccab13947 | 47 | |
lixianyu | 1:758ccab13947 | 48 | return this->_motor_vol; |
lixianyu | 1:758ccab13947 | 49 | } |
lixianyu | 1:758ccab13947 | 50 | |
lixianyu | 1:758ccab13947 | 51 | |
lixianyu | 1:758ccab13947 | 52 | void Motor::Driver(int16_t _motor_driver) |
lixianyu | 1:758ccab13947 | 53 | { |
lixianyu | 1:758ccab13947 | 54 | int8_t channel_A = motors[this->motorIndex].Pin.nbr_A; |
lixianyu | 1:758ccab13947 | 55 | int8_t channel_B = motors[this->motorIndex].Pin.nbr_B; |
lixianyu | 1:758ccab13947 | 56 | if (_motor_driver == 0) { |
lixianyu | 1:758ccab13947 | 57 | digitalWrite(channel_A, LOW); |
lixianyu | 1:758ccab13947 | 58 | digitalWrite(channel_B, LOW); |
lixianyu | 1:758ccab13947 | 59 | } else if (_motor_driver > 0) { |
lixianyu | 1:758ccab13947 | 60 | analogWrite(channel_A, _motor_driver); |
lixianyu | 1:758ccab13947 | 61 | digitalWrite(channel_B, LOW); |
lixianyu | 1:758ccab13947 | 62 | } else { |
lixianyu | 1:758ccab13947 | 63 | analogWrite(channel_A, 255 + _motor_driver); |
lixianyu | 1:758ccab13947 | 64 | digitalWrite(channel_B, HIGH); |
lixianyu | 1:758ccab13947 | 65 | } |
lixianyu | 1:758ccab13947 | 66 | } |
lixianyu | 1:758ccab13947 | 67 | |
lixianyu | 1:758ccab13947 | 68 | void Motor::Free() |
lixianyu | 1:758ccab13947 | 69 | { |
lixianyu | 1:758ccab13947 | 70 | int8_t channel_A = motors[this->motorIndex].Pin.nbr_A; |
lixianyu | 1:758ccab13947 | 71 | int8_t channel_B = motors[this->motorIndex].Pin.nbr_B; |
lixianyu | 1:758ccab13947 | 72 | digitalWrite(channel_A, LOW); |
lixianyu | 1:758ccab13947 | 73 | digitalWrite(channel_B, LOW); |
lixianyu | 1:758ccab13947 | 74 | } |
lixianyu | 1:758ccab13947 | 75 | |
lixianyu | 1:758ccab13947 | 76 | void Motor::Brake() |
lixianyu | 1:758ccab13947 | 77 | { |
lixianyu | 1:758ccab13947 | 78 | int8_t channel_A = motors[this->motorIndex].Pin.nbr_A; |
lixianyu | 1:758ccab13947 | 79 | int8_t channel_B = motors[this->motorIndex].Pin.nbr_B; |
lixianyu | 1:758ccab13947 | 80 | digitalWrite(channel_A, HIGH); |
lixianyu | 1:758ccab13947 | 81 | digitalWrite(channel_B, HIGH); |
lixianyu | 1:758ccab13947 | 82 | } |