![](/media/cache/img/default_profile.jpg.50x50_q85.jpg)
Microduino的cube小车。
Diff: Microduino_Motor.cpp
- Revision:
- 3:e4ac7c1a14de
- Parent:
- 2:70ca3e685cca
- Child:
- 4:0670023d3f36
--- a/Microduino_Motor.cpp Wed May 25 13:25:09 2016 +0000 +++ b/Microduino_Motor.cpp Fri May 27 01:44:31 2016 +0000 @@ -10,18 +10,28 @@ this->motorIndex = MotorCount++; // assign a key index to this instance //if (_motor_pinA < NUM_DIGITAL_PINS && _motor_pinB < NUM_DIGITAL_PINS) { if (true) { - //pinMode( _motor_pinA, OUTPUT) ; - gpio_init_out(&gpioA, _motor_pinA); +#if 0 + pinMode( _motor_pinA, OUTPUT) ; +#else + _period_us = 2000; // 500Hz + pwmout_init(&_pwmA, _motor_pinA); + pwmout_period_us(&_pwmA, _period_us); // 500Hz +#endif motors[this->motorIndex].Pin.nbr_A = _motor_pinA; - //pinMode( _motor_pinB, OUTPUT) ; - gpio_init_out(&gpioB, _motor_pinB); +#if 0 + pinMode( _motor_pinB, OUTPUT) ; +#else + pwmout_init(&_pwmB, _motor_pinB); + pwmout_period_us(&_pwmB, _period_us); // 500Hz +#endif motors[this->motorIndex].Pin.nbr_B = _motor_pinB; this->fix=1; } - } else + } else { this->motorIndex = 255 ; // too many keys + } } void Motor::Fix(float _fix) @@ -48,7 +58,7 @@ return this->_motor_vol; } - +#if 0 void Motor::Driver(int16_t _motor_driver) { int8_t channel_A = motors[this->motorIndex].Pin.nbr_A; @@ -64,19 +74,50 @@ digitalWrite(channel_B, HIGH); } } +#else +void Motor::Driver(int16_t _motor_driver) +{ + int16_t pulseWidth = 0; + PinName channel_A = motors[this->motorIndex].Pin.nbr_A; + PinName channel_B = motors[this->motorIndex].Pin.nbr_B; + if (_motor_driver == 0) { + pwmout_pulsewidth_us(&_pwmA, 0); + pwmout_pulsewidth_us(&_pwmB, 0); + } else if (_motor_driver > 0) { + pulseWidth = _period_us * _motor_driver / 255; + pwmout_pulsewidth_us(&_pwmA, pulseWidth); + pwmout_pulsewidth_us(&_pwmB, 0); + } else { + _motor_driver = 255 + _motor_driver; + pulseWidth = _period_us * _motor_driver / 255; + pwmout_pulsewidth_us(&_pwmA, pulseWidth); + pwmout_pulsewidth_us(&_pwmB, _period_us); + } +} +#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