LPC824

Dependencies:   mbed

Fork of CubeFine by wu le

Committer:
beian10
Date:
Mon Jul 04 07:17:39 2016 +0000
Revision:
2:7964622fb5a5
Parent:
1:54a2d380f8c7
V2

Who changed what in which revision?

UserRevisionLine numberNew contents of line
lixianyu 0:362c1482232c 1 #include "Microduino_Motor.h"
lixianyu 0:362c1482232c 2
lixianyu 0:362c1482232c 3 Motor::Motor(PinName _motor_pinA, PinName _motor_pinB)
lixianyu 0:362c1482232c 4 {
lixianyu 0:362c1482232c 5 _period_us = 255; // 500Hz
lixianyu 0:362c1482232c 6 pwmout_init(&_pwmA, _motor_pinA);
lixianyu 0:362c1482232c 7 pwmout_period_us(&_pwmA, _period_us); // 500Hz
beian10 2:7964622fb5a5 8 pwmout_pulsewidth_us(&_pwmA, 0);
lixianyu 0:362c1482232c 9
beian10 1:54a2d380f8c7 10
beian10 2:7964622fb5a5 11 gpio_init_out(&gpioB, _motor_pinB);
lixianyu 0:362c1482232c 12
lixianyu 0:362c1482232c 13 this->fix=1;
lixianyu 0:362c1482232c 14 }
lixianyu 0:362c1482232c 15
lixianyu 0:362c1482232c 16 void Motor::Fix(float _fix)
lixianyu 0:362c1482232c 17 {
lixianyu 0:362c1482232c 18 this->fix=_fix;
lixianyu 0:362c1482232c 19 }
lixianyu 0:362c1482232c 20
lixianyu 0:362c1482232c 21 int16_t Motor::GetData(int16_t _throttle, int16_t _steering, uint8_t _dir)
lixianyu 0:362c1482232c 22 {
lixianyu 0:362c1482232c 23 this->_motor_vol = _throttle;
lixianyu 0:362c1482232c 24
lixianyu 0:362c1482232c 25 if(_dir == 1)
lixianyu 0:362c1482232c 26 {
lixianyu 0:362c1482232c 27 this->_motor_vol -= _steering / 2;
lixianyu 0:362c1482232c 28 }
lixianyu 0:362c1482232c 29 else
lixianyu 0:362c1482232c 30 {
lixianyu 0:362c1482232c 31 this->_motor_vol += _steering / 2;
lixianyu 0:362c1482232c 32 }
lixianyu 0:362c1482232c 33 if (this->_motor_vol > 255)
lixianyu 0:362c1482232c 34 this->_motor_vol = 255;
lixianyu 0:362c1482232c 35 else if (this->_motor_vol < -255)
lixianyu 0:362c1482232c 36 this->_motor_vol = -255;
lixianyu 0:362c1482232c 37
beian10 2:7964622fb5a5 38 this->_motor_vol *= fix;
lixianyu 0:362c1482232c 39
lixianyu 0:362c1482232c 40 return this->_motor_vol;
lixianyu 0:362c1482232c 41 }
lixianyu 0:362c1482232c 42
lixianyu 0:362c1482232c 43 void Motor::Driver(int16_t _motor_driver)
lixianyu 0:362c1482232c 44 {
lixianyu 0:362c1482232c 45 uint32_t pulseWidth = 0;
beian10 2:7964622fb5a5 46
lixianyu 0:362c1482232c 47 if (_motor_driver == 0) {
lixianyu 0:362c1482232c 48 pwmout_pulsewidth_us(&_pwmA, 0);
beian10 2:7964622fb5a5 49 gpio_write(&gpioB, 0);
lixianyu 0:362c1482232c 50 } else if (_motor_driver > 0) {
lixianyu 0:362c1482232c 51 pulseWidth = _period_us / 255 * _motor_driver;
lixianyu 0:362c1482232c 52 pwmout_pulsewidth_us(&_pwmA, pulseWidth);
beian10 2:7964622fb5a5 53 gpio_write(&gpioB, 0);
lixianyu 0:362c1482232c 54 } else {
beian10 2:7964622fb5a5 55 //_motor_driver = abs(_motor_driver);
beian10 2:7964622fb5a5 56 pulseWidth = _period_us / 255 * (255 + _motor_driver);
beian10 2:7964622fb5a5 57 pwmout_pulsewidth_us(&_pwmA, pulseWidth);
beian10 2:7964622fb5a5 58 gpio_write(&gpioB, 1);
lixianyu 0:362c1482232c 59 }
lixianyu 0:362c1482232c 60 }
lixianyu 0:362c1482232c 61
lixianyu 0:362c1482232c 62 void Motor::Free()
lixianyu 0:362c1482232c 63 {
lixianyu 0:362c1482232c 64 pwmout_pulsewidth_us(&_pwmA, 0);
beian10 2:7964622fb5a5 65 gpio_write(&gpioB, 0);
lixianyu 0:362c1482232c 66 }
lixianyu 0:362c1482232c 67
lixianyu 0:362c1482232c 68 void Motor::Brake()
lixianyu 0:362c1482232c 69 {
lixianyu 0:362c1482232c 70 pwmout_pulsewidth_us(&_pwmA, _period_us);
beian10 2:7964622fb5a5 71 gpio_write(&gpioB, 1);
lixianyu 0:362c1482232c 72 }