03_main.ino 2.6 KB

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