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.

68 lines
2.6 KiB

  1. /*
  2. * Created by: Cheng Saetern
  3. * This example is meant to demonstrate the ability to adjust pwm frequency and/or
  4. * resolution for Arduino Nano/Uno pin 9 and 10 using function setPWM16(uint8_t prescaler, unsigned int resolution).
  5. * Equation for fast pwm frequency = frequency of MPU(16Mhz)/prescaler/resolution
  6. * F_PWM = 16000000/prescaler/resolution.
  7. * prescaler argument value MUST be between 1-5, representing 1,8,64,256,1024 respectively.
  8. * resolution MUST be a value from 0-65535.
  9. */
  10. #include <MX1508.h>
  11. #define PINA 9
  12. #define PINB 10
  13. #define NUMPWM 2
  14. // MX1508 schematics(in Chinese) can be found here at: http://sales.dzsc.com/486222.html
  15. /*
  16. * MX1508(uint8_t pinIN1, uint8_t pinIN2, DecayMode decayMode, NumOfPwmPins numPWM);
  17. * DecayMode must be FAST_DECAY or SLOW_DECAY,
  18. * NumOfPwmPins, must be the value of 2 for setPWM16() function
  19. * PINA and PINB MUST!!! be pin 9 and 10 for setPWM16() function
  20. * Example MX1508 myMotor(10,9,FAST_DECAY, 2).
  21. */
  22. MX1508 motorA(PINA,PINB, FAST_DECAY, 2);
  23. int resolution = 1000;
  24. void setup() {
  25. Serial.begin(115200);
  26. motorA.setPWM16(2,resolution); // prescaler at 8, resolution 1000, PWM frequency = 16Mhz/8/1000=2000Hz
  27. // prescalar 1=1, 2=8, 3=64, 4=256, 5 =1028
  28. /*------------ setPWM16 Class function is defined as below-----------------
  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 ;
  34. ICR1 = resolution;
  35. _pwmResolution = resolution;
  36. _useAnalogWrite16 = true;
  37. }
  38. */
  39. }
  40. /*
  41. * Ramp up to pwm = resolution/2 , by increasing pwm by 1 every 50 millisecond.
  42. * then ramp down to pwm = -resolution/2, by decreasing pwm every 50 millisecond.
  43. * positive value pwm results in forward direction.
  44. * negative value pwm results in opposite direction.
  45. */
  46. void loop() {
  47. // put your main code here, to run repeatedly:
  48. static unsigned long lastMilli = 0;
  49. static bool cwDirection = true; // assume initial direction(positive pwm) is clockwise
  50. static int pwm = 1;
  51. if(millis()-lastMilli > 50){ // every 50 millisecond
  52. if (cwDirection && pwm++ > resolution/2 ) {
  53. cwDirection = false;
  54. } else if (!cwDirection && pwm-- < -(resolution/2)) {
  55. cwDirection = true;
  56. }
  57. motorA.motorGo(pwm);
  58. lastMilli = millis();
  59. Serial.println(motorA.getPWM()); // we can just print pwm but just showing that member function getPWM() works.
  60. }
  61. }