02_main.ino 2.4 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697
  1. char outputStr[100];
  2. int16_t averages[AVG_PERIODS];
  3. void loop() {
  4. #ifdef SCAN_MODE
  5. for(byte i = LOW_CHANNEL; i <= NUM_CHANNELS; i++) {
  6. readChannel(i);
  7. }
  8. #else
  9. Serial.println("============");
  10. int throttle = getThrottle();
  11. throttle = restrictThrottlePower(throttle);
  12. throttle = getAverage(throttle);
  13. digitalWrite(LEFT_MOTOR_DIRECT_PIN, throttle > 0 ? HIGH : LOW);
  14. analogWrite(LEFT_MOTOR_PIN, throttle > 0 ? throttle : -throttle);
  15. #endif
  16. Serial.println();
  17. delay(SCAN_DELAY);
  18. }
  19. #define TIMEOUT_MICROS 30000
  20. uint16_t readChannel(byte channel) {
  21. int val = pulseIn(channels[channel], HIGH, TIMEOUT_MICROS);
  22. #ifdef SCAN_MODE
  23. if(val > 100) val -= 1000;
  24. if(channel > 1) Serial.print(" ");
  25. Serial.print(val);
  26. #else
  27. sprintf(outputStr, "Channel %d:\t%d", channel, val);
  28. Serial.println(outputStr);
  29. #endif
  30. return val;
  31. }
  32. const int throtDeadHigh = THROT_NONE + THROT_DEAD_ZONE,
  33. throtDeadLow = THROT_NONE - THROT_DEAD_ZONE;
  34. int getThrottle() {
  35. int val = readChannel(THROT_CHANNEL);
  36. Serial.print("Channel value: ");
  37. Serial.print(val);
  38. Serial.print("\t");
  39. if(val <= THROT_OFF) {
  40. Serial.println("Throttle is off");
  41. return 0;
  42. } else if(val < throtDeadHigh && val > throtDeadLow) {
  43. Serial.println("Throttle in dead zone");
  44. return 0;
  45. }
  46. int throttle = val < THROT_NONE
  47. ? map(val, THROT_MIN, THROT_NONE, -OUTPUT_RANGE, 0)
  48. : map(val, THROT_NONE, THROT_MAX, 0, OUTPUT_RANGE);
  49. throttle = constrain(throttle, -OUTPUT_RANGE, OUTPUT_RANGE);
  50. Serial.print("Throttle: ");
  51. Serial.println(throttle);
  52. return throttle;
  53. }
  54. int restrictThrottlePower(int throttle) {
  55. // Reduce the average voltage to something safe for the motor to consume.
  56. throttle = (throttle * MAX_POWER_PERCENT) / 100;
  57. Serial.print("Restricted throttle:\t");
  58. Serial.println(throttle);
  59. // Use the current value of the knob to reduce the speed.
  60. int speedKnob = readChannel(SPEED_CHANNEL);
  61. speedKnob = map(speedKnob, SPEED_MIN, SPEED_MAX, 0, 100);
  62. speedKnob = constrain(speedKnob, 0, 100);
  63. throttle = (throttle * speedKnob) / 100;
  64. Serial.print("Speed knob:\t");
  65. Serial.println(speedKnob);
  66. Serial.print("Speed adjusted throttle:\t");
  67. Serial.println(throttle);
  68. return throttle;
  69. }
  70. int getAverage(const int throttle) {
  71. int total = throttle;
  72. for(byte i = 0; i < AVG_PERIODS-1; i++) {
  73. total += averages[i];
  74. averages[i] = averages[i+1];
  75. }
  76. averages[AVG_PERIODS-1] = throttle;
  77. total /= AVG_PERIODS;
  78. Serial.print("Average adjusted throttle:\t");
  79. Serial.println(total);
  80. return total;
  81. }