rc_receiver_driving.ino 4.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177
  1. //#define SCAN_MODE // If set, scan & output channel values, rather than driving the robot.
  2. /////////////////////////////////////////////////////////////////////////
  3. // Configuration
  4. //////////////////////////////////////////////////
  5. #define MAX_POWER_PERCENT 90 // The maximum percentage on time, used to decrease average voltage to the motor.
  6. #define OUTPUT_RANGE 255 // The maximum value for PWM output
  7. ///////////////////////
  8. #define SCAN_DELAY 100 // Delay between updates in ms
  9. #define AVG_PERIODS 10 // Number of periods to average the speed over (reduces random variances)
  10. /////////////////////////////////////////////////////////////////////////
  11. // Channel pins
  12. /////////////////////////////////////////////////////////////////////////
  13. #define LOW_CHANNEL 1
  14. #define NUM_CHANNELS 6
  15. // Channel pins. Using numbers 1-6 for clarity, so using a bad value in index 0.
  16. const byte channels[7] = {255, 8,9,10,11,12,13};
  17. /////////////////////////////////////////////////////////////////////////
  18. // Channel values
  19. /////////////////////////////////////////////////////////////////////////
  20. // Right horizontal (steering)
  21. #define STEER_CHANNEL 1
  22. #define STEER_LEFT 1300
  23. #define STEER_RIGHT 1690
  24. #define STEER_NONE 1500
  25. #define STEER_DEAD_ZONE 30 // 10% of the range is dead zone
  26. // Right vertical (throttle)
  27. #define THROT_CHANNEL 2
  28. #define THROT_MAX 1940
  29. #define THROT_MIN 1160
  30. #define THROT_NONE 1510// Halfway range
  31. #define THROT_DEAD_ZONE 30 // approx 10% of the range is dead
  32. #define THROT_OFF 0 // Anything below this means the throttle switch (upper right) is off
  33. #define CH_4_MIN 0
  34. #define CH_4_MAX 0
  35. // Right knob
  36. #define LIGHT_CHANNEL 5
  37. #define LIGHT_MIN 990
  38. #define LIGHT_MAX 1990
  39. // Left knob
  40. #define SPEED_CHANNEL 6
  41. #define SPEED_MIN 1000
  42. #define SPEED_MAX 2000
  43. /////////////////////////////////////////////////////////////////////////
  44. // Output pins
  45. /////////////////////////////////////////////////////////////////////////
  46. #define LEFT_MOTOR_PIN 5
  47. #define LEFT_MOTOR_DIRECT_PIN 4
  48. #define RIGHT_MOTOR_PIN 6
  49. #define RIGHT_MOTOR_DIRECT_PIN 7
  50. char outputStr[100];
  51. int16_t averages[AVG_PERIODS];
  52. void setup() {
  53. Serial.begin(9600);
  54. pinMode(LEFT_MOTOR_PIN, OUTPUT);
  55. pinMode(RIGHT_MOTOR_PIN, OUTPUT);
  56. pinMode(LEFT_MOTOR_DIRECT_PIN, OUTPUT);
  57. pinMode(RIGHT_MOTOR_DIRECT_PIN, OUTPUT);
  58. for(byte i = LOW_CHANNEL; i <= NUM_CHANNELS; i++) {
  59. pinMode(channels[i], INPUT);
  60. }
  61. delay(2000);
  62. }
  63. void loop() {
  64. #ifdef SCAN_MODE
  65. for(byte i = LOW_CHANNEL; i <= NUM_CHANNELS; i++) {
  66. readChannel(i);
  67. }
  68. #else
  69. Serial.println("============");
  70. int throttle = getThrottle();
  71. throttle = restrictThrottlePower(throttle);
  72. throttle = getAverage(throttle);
  73. digitalWrite(LEFT_MOTOR_DIRECT_PIN, throttle > 0 ? HIGH : LOW);
  74. analogWrite(LEFT_MOTOR_PIN, throttle > 0 ? throttle : -throttle);
  75. #endif
  76. Serial.println();
  77. delay(SCAN_DELAY);
  78. }
  79. #define TIMEOUT_MICROS 30000
  80. uint16_t readChannel(byte channel) {
  81. int val = pulseIn(channels[channel], HIGH, TIMEOUT_MICROS);
  82. #ifdef SCAN_MODE
  83. if(val > 100) val -= 1000;
  84. if(channel > 1) Serial.print(" ");
  85. Serial.print(val);
  86. #else
  87. sprintf(outputStr, "Channel %d:\t%d", channel, val);
  88. Serial.println(outputStr);
  89. #endif
  90. return val;
  91. }
  92. const int throtDeadHigh = THROT_NONE + THROT_DEAD_ZONE,
  93. throtDeadLow = THROT_NONE - THROT_DEAD_ZONE;
  94. int getThrottle() {
  95. int val = readChannel(THROT_CHANNEL);
  96. Serial.print("Channel value: ");
  97. Serial.print(val);
  98. Serial.print("\t");
  99. if(val <= THROT_OFF) {
  100. Serial.println("Throttle is off");
  101. return 0;
  102. } else if(val < throtDeadHigh && val > throtDeadLow) {
  103. Serial.println("Throttle in dead zone");
  104. return 0;
  105. }
  106. int throttle = val < THROT_NONE
  107. ? map(val, THROT_MIN, THROT_NONE, -OUTPUT_RANGE, 0)
  108. : map(val, THROT_NONE, THROT_MAX, 0, OUTPUT_RANGE);
  109. throttle = constrain(throttle, -OUTPUT_RANGE, OUTPUT_RANGE);
  110. Serial.print("Throttle: ");
  111. Serial.println(throttle);
  112. return throttle;
  113. }
  114. int restrictThrottlePower(int throttle) {
  115. // Reduce the average voltage to something safe for the motor to consume.
  116. throttle = (throttle * MAX_POWER_PERCENT) / 100;
  117. Serial.print("Restricted throttle:\t");
  118. Serial.println(throttle);
  119. // Use the current value of the knob to reduce the speed.
  120. int speedKnob = readChannel(SPEED_CHANNEL);
  121. speedKnob = map(speedKnob, SPEED_MIN, SPEED_MAX, 0, 100);
  122. speedKnob = constrain(speedKnob, 0, 100);
  123. throttle = (throttle * speedKnob) / 100;
  124. Serial.print("Speed knob:\t");
  125. Serial.println(speedKnob);
  126. Serial.print("Speed adjusted throttle:\t");
  127. Serial.println(throttle);
  128. return throttle;
  129. }
  130. int getAverage(const int throttle) {
  131. int total = throttle;
  132. for(byte i = 0; i < AVG_PERIODS-1; i++) {
  133. total += averages[i];
  134. averages[i] = averages[i+1];
  135. }
  136. averages[AVG_PERIODS-1] = throttle;
  137. total /= AVG_PERIODS;
  138. Serial.print("Average adjusted throttle:\t");
  139. Serial.println(total);
  140. return total;
  141. }