03_main.ino 5.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201
  1. char outputStr[100];
  2. int16_t leftAverages[AVG_PERIODS];
  3. int16_t rightAverages[AVG_PERIODS];
  4. const int throtDeadHigh = THROT_NONE + THROT_DEAD_ZONE,
  5. throtDeadLow = THROT_NONE - THROT_DEAD_ZONE;
  6. const int steerDeadHigh = STEER_NONE + STEER_DEAD_ZONE,
  7. steerDeadLow = STEER_NONE - STEER_DEAD_ZONE;
  8. void loop() {
  9. const long startTime = millis();
  10. deadmanSwitch();
  11. #ifdef SCAN_MODE
  12. for(byte ch = LOW_CHANNEL; ch <= NUM_CHANNELS; ch++) {
  13. int val = channelVals[ch];
  14. sprintf(outputStr, "Channel-%d:%d\t", ch, val);
  15. Serial.print(outputStr);
  16. }
  17. Serial.println();
  18. #else
  19. debugln();
  20. debugln("===================");
  21. int throttle = getThrottle(),
  22. steer = getSteering();
  23. driveWheel(throttle, steer, LEFT),
  24. driveWheel(throttle, steer, RIGHT);
  25. Serial.println();
  26. #endif
  27. const long now = millis();
  28. const long sleepTime = SCAN_DELAY + (startTime - now);
  29. delay(sleepTime);
  30. }
  31. /**
  32. * Return the throttle value between -THROT_RANGE (reverse) and +THROT_RANGE (forward)
  33. */
  34. int getThrottle() {
  35. int val = channelVals[THROT_CHANNEL];
  36. debug("Channel value: ");
  37. debug(val);
  38. debug("\t");
  39. if(val <= THROT_OFF) {
  40. debugln("Throttle is off");
  41. return 0;
  42. } else if(val < throtDeadHigh && val > throtDeadLow) {
  43. debugln("Throttle in dead zone");
  44. return 0;
  45. }
  46. // Map the value to a value from 0 to THROT_RANGE range (or -THROT_RANGE to 0)
  47. int throttle = val < THROT_NONE
  48. ? map(val, THROT_MIN, THROT_NONE, -THROT_RANGE, 0)
  49. : map(val, THROT_NONE, THROT_MAX, 0, THROT_RANGE);
  50. // Constrain the value in case the receiver outputs a value
  51. // outside the expected range.
  52. throttle = constrain(throttle, -THROT_RANGE, THROT_RANGE);
  53. debugln("Throttle: ", throttle);
  54. return throttle;
  55. }
  56. /**
  57. * Get the value for steering, between -STEER_RANGE (left) and +STEER_RANGE (right).
  58. */
  59. int getSteering() {
  60. int val = channelVals[STEER_CHANNEL];
  61. debug("Steer channel: ");
  62. debug(val);
  63. debug("\t");
  64. if(val < steerDeadHigh && val > throtDeadLow) {
  65. debugln("Steering in dead zone");
  66. return 0;
  67. }
  68. // Map the value to a value from 0 to STEER_RANGE range (or -STEER_RANGE to 0)
  69. int steer = val < STEER_NONE
  70. ? map(val, STEER_LEFT, STEER_NONE, -STEER_RANGE, 0)
  71. : map(val, STEER_NONE, STEER_RIGHT, 0, STEER_RANGE);
  72. // Constrain the value in case the receiver outputs a value
  73. // outside the expected range.
  74. steer = constrain(steer, -STEER_RANGE, STEER_RANGE);
  75. debugln("Steer: ", steer);
  76. return steer;
  77. }
  78. /**
  79. * Restrict the motor power based on the speed control dial.
  80. * Takes int from 0-255
  81. * Returns int 0-255
  82. */
  83. int restrictThrottlePower(long throttle) {
  84. // Reduce the average voltage to something safe for the motor to consume.
  85. throttle = (throttle * MAX_POWER_PERCENT) / 100;
  86. debugln("Restricted throttle:\t", throttle);
  87. // Use the current value of the knob to reduce the speed.
  88. int speedKnob = channelVals[SPEED_CHANNEL];
  89. speedKnob = map(speedKnob, SPEED_MIN, SPEED_MAX, 0, 100);
  90. speedKnob = constrain(speedKnob, 0, 100);
  91. throttle = (throttle * speedKnob) / 100;
  92. debugln("Speed knob:\t", speedKnob);
  93. debugln("Speed adjusted throttle:\t", throttle);
  94. throttle = map(throttle, -THROT_RANGE, THROT_RANGE, -OUTPUT_RANGE, OUTPUT_RANGE);
  95. debugln("Range adjusted throttle:\t", throttle);
  96. return throttle;
  97. }
  98. /**
  99. * Get the average throttle for the last AVG_OVER_MILLIS ms
  100. *
  101. * Input: value from 0-255
  102. * Return: value from 0-255
  103. */
  104. int getAverage(const int throttle, int16_t* averages) {
  105. long long total = throttle;
  106. for(byte i = 0; i < AVG_PERIODS-1; i++) {
  107. total += averages[i];
  108. averages[i] = averages[i+1];
  109. }
  110. averages[AVG_PERIODS-1] = throttle;
  111. total /= AVG_PERIODS;
  112. debugln("Average adjusted throttle:\t", total);
  113. return total;
  114. }
  115. /**
  116. * Using the current throttle and steering values, determine the needed output
  117. * value for a given wheel (LEFT or RIGHT), then drive that motor.
  118. */
  119. int driveWheel(int throttle, const int steer, const byte wheel) {
  120. // Negative steer = turn left = left backwards + right forwards
  121. // Positive steer = turn right = left forwards + right backwards
  122. int16_t* averages;
  123. debugln();
  124. switch(wheel) {
  125. case LEFT:
  126. debugln(F("=== LEFT ==="));
  127. Serial.print(F("Left:"));
  128. throttle += steer;
  129. averages = leftAverages;
  130. break;
  131. case RIGHT:
  132. debugln();
  133. debugln(F("=== RIGHT ==="));
  134. Serial.print(F("Right:"));
  135. throttle -= steer;
  136. averages = rightAverages;
  137. break;
  138. }
  139. debugln("Adjusted throttle:\t", throttle);
  140. // Make sure steering didn't throw it out of range
  141. throttle = constrain(throttle, -THROT_RANGE, THROT_RANGE);
  142. debugln("Constrained throttle:\t", throttle);
  143. // Restrict it to the max power dial
  144. throttle = restrictThrottlePower(throttle);
  145. // Average the power so it doesn't overwhelm the wheel
  146. throttle = getAverage(throttle, averages);
  147. debug("Wheel power: ");
  148. Serial.print(throttle);
  149. Serial.print(F("\t"));
  150. digitalWrite(
  151. wheel == LEFT ? LEFT_MOTOR_DIRECT_PIN : RIGHT_MOTOR_DIRECT_PIN,
  152. throttle > 0 ? HIGH : LOW
  153. );
  154. analogWrite(
  155. wheel == LEFT ? LEFT_MOTOR_PIN : RIGHT_MOTOR_PIN,
  156. throttle > 0 ? throttle : -throttle);
  157. }