Ein Roboter mit bürstenlosem Antrieb, differenzial und NRF24L01 Funk. Großflächig gebaut um ein großes Solarpanel aufzunehmen. https://gitlab.informatik.hs-fulda.de/fdai5253/roboter
You can not select more than 25 topics Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.

100 lines
3.1 KiB

  1. #include "MX1508.h"
  2. MX1508::MX1508( uint8_t pinIN1, uint8_t pinIN2) {
  3. _pinIN1 = pinIN1; // always a PWM pin
  4. _pinIN2 = pinIN2; // can be a non-Pwm pin.
  5. _whichMode = FAST_DECAY;
  6. _numPwmPins = PWM_2PIN;
  7. pinMode(_pinIN1, OUTPUT);
  8. pinMode(_pinIN2, OUTPUT);
  9. }
  10. MX1508::MX1508( uint8_t pinIN1, uint8_t pinIN2, DecayMode decayMode, NumOfPwmPins numPins) {
  11. _pinIN1 = pinIN1; // always a PWM pin
  12. _pinIN2 = pinIN2; // can be a non-Pwm pin.
  13. _whichMode = decayMode;
  14. _numPwmPins = numPins;
  15. pinMode(_pinIN1, OUTPUT);
  16. pinMode(_pinIN2, OUTPUT);
  17. }
  18. int MX1508::getPWM() {
  19. return _pwmVal;
  20. }
  21. void MX1508::stopMotor() {
  22. digitalWrite(_pinIN1, LOW);
  23. digitalWrite(_pinIN2, LOW);
  24. }
  25. void MX1508::setResolution(unsigned int pwmResolution) {
  26. _pwmResolution = pwmResolution;
  27. if(_useAnalogWrite16) ICR1 = pwmResolution;
  28. }
  29. void MX1508::setPWM16(uint8_t prescaler, unsigned int resolution){
  30. if(prescaler > 5 || prescaler == 0) prescaler = 3; // default to 64 if not in range.
  31. DDRB |= _BV(PB1) | _BV(PB2); /* set pin 9and 10 as outputs */
  32. TCCR1A = _BV(COM1A1) | _BV(COM1B1) | _BV(WGM11); // non-inverting PWM, mode 14 fastPWM, TOP =ICR1
  33. TCCR1B = _BV(WGM13) | _BV(WGM12) | prescaler ; // rescaler must be 1->5, 1,8,64,256,1028 respectively
  34. ICR1 = resolution;
  35. _pwmResolution = resolution;
  36. _useAnalogWrite16 = true;
  37. }
  38. void MX1508::analogWrite16(uint8_t pin, uint16_t val)
  39. {
  40. if(_useAnalogWrite16){
  41. if(val < 5) val =5;
  42. switch (pin) {
  43. case 9: OCR1A = val; break;
  44. case 10: OCR1B = val; break;
  45. default: analogWrite(pin,val);
  46. }
  47. }else{
  48. analogWrite(pin, val);
  49. }
  50. }
  51. void MX1508::motorGo(long pwmSpeed) {
  52. _pwmVal = pwmSpeed;
  53. if(pwmSpeed == 0) {
  54. this->stopMotor();
  55. } else {
  56. // if set decay mode is set as fast decay mode
  57. if (this->_whichMode == FAST_DECAY) {
  58. if (pwmSpeed >= 0) { //forward fast decay
  59. if(_numPwmPins == PWM_1PIN)digitalWrite(_pinIN2, LOW);
  60. else analogWrite16(_pinIN2, 1);
  61. analogWrite16(_pinIN1, pwmSpeed);
  62. } else if (this->_numPwmPins == PWM_2PIN) { // reverse fast decay
  63. pwmSpeed *= -1;
  64. analogWrite16(_pinIN1, 1);
  65. analogWrite16(_pinIN2, pwmSpeed);
  66. } else if (this->_numPwmPins == PWM_1PIN) { // reverse slow decay
  67. pwmSpeed *= -1;
  68. pwmSpeed = map(pwmSpeed, 0, _pwmResolution, _pwmResolution, 0);
  69. digitalWrite(_pinIN2, HIGH);
  70. analogWrite16(_pinIN1, pwmSpeed);
  71. }
  72. }
  73. // if decay mode is set as slow decay mode
  74. else {
  75. if (pwmSpeed >= 0) { // forward slow decay
  76. pwmSpeed = map(pwmSpeed, 0, _pwmResolution, _pwmResolution, 0);
  77. if(_numPwmPins == PWM_1PIN)digitalWrite(_pinIN1, HIGH);
  78. else analogWrite16(_pinIN1, _pwmResolution);
  79. analogWrite16(_pinIN2, pwmSpeed);
  80. } else if (this->_numPwmPins == PWM_2PIN) { // reverse slow decay
  81. pwmSpeed *= -1;
  82. pwmSpeed = map(pwmSpeed, 0, _pwmResolution, _pwmResolution, 0);
  83. analogWrite16(_pinIN2, _pwmResolution);
  84. analogWrite16(_pinIN1, pwmSpeed);
  85. } else if (this->_numPwmPins == PWM_1PIN) { // reverse fast decay
  86. pwmSpeed *= -1;
  87. digitalWrite(_pinIN1, LOW);
  88. analogWrite16(_pinIN2, pwmSpeed);
  89. }
  90. }
  91. }
  92. }