Naze32 clone with Frysky receiver
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.

cppm.c 3.3KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131
  1. /*
  2. * Combined-PPM signal generator
  3. *
  4. * The whole CPPM pulse should be 20ms long.
  5. * It contains 8 channels with 2ms each, followed
  6. * by 4ms of silence. One channel pulse varies between
  7. * 1 and 2 ms. They are seperated with a very short low
  8. * pulse of about 0.1ms.
  9. *
  10. * 20.000us
  11. * - 8 * 2.000us = 16.000us
  12. * - 9 * 100us = 900us
  13. * = 3.100us
  14. *
  15. * 1 2 3 4 5 6 7 8
  16. * ___ ___ ___ ___ ___ ___ ___ ___ __________
  17. * | | | | | | | | | | | | | | | | | | |
  18. * | | | | | | | | | | | | | | | | | | |
  19. * | | | | | | | | | | | | | | | | | | |
  20. * |_| |_| |_| |_| |_| |_| |_| |_| |_| |
  21. *
  22. * States:
  23. * 0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17
  24. */
  25. #include <avr/io.h>
  26. #include <avr/interrupt.h>
  27. #include "cppm.h"
  28. #define MAX_STATES 17
  29. #define CHANNELS 8
  30. #define WHOLE_PULSE_WIDTH 20000
  31. #define PULSE_WIDTH 2000
  32. #define MAX_PULSE_WIDTH (CHANNELS * PULSE_WIDTH) // 16.000
  33. #define PULSE_LOW 100
  34. #define PULSE_LOW_SUM ((CHANNELS + 1) * PULSE_LOW) // 900
  35. #define MIN_WAIT (WHOLE_PULSE_WIDTH - MAX_PULSE_WIDTH - PULSE_LOW_SUM) // 3100
  36. #define TIME_AFTER_OVERFLOW 128
  37. #define TIME_MULTIPLIER 2
  38. volatile uint16_t cppmData[CHANNELS] = { 1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500 };
  39. volatile uint16_t delaySum = 0;
  40. volatile uint8_t state = 0;
  41. volatile uint16_t triggerTimeRemaining = 0;
  42. #define NONE 0
  43. #define COMPARE_MATCH 1
  44. #define OVERFLOW 2
  45. volatile uint8_t triggerState = NONE;
  46. static void triggerIn(uint16_t us);
  47. static void nextState(void);
  48. void cppmInit(void) {
  49. // Set pin to output mode
  50. CPPM_DDR |= (1 << CPPM_PIN);
  51. // Start with a low pulse
  52. CPPM_PORT &= ~(1 << CPPM_PIN);
  53. TCCR0B |= (1 << CS01); // Prescaler: 8
  54. TIMSK |= (1 << TOIE0) | (1 << OCIE0A); // Enable Overflow and Compare Match Interrupt
  55. OCR0A = 0;
  56. state = 0;
  57. delaySum = MIN_WAIT;
  58. triggerIn(PULSE_LOW);
  59. }
  60. void cppmCopy(uint16_t *data) {
  61. cli();
  62. for (int i = 0; i < CHANNELS; i++) {
  63. cppmData[i] = data[i];
  64. }
  65. sei();
  66. }
  67. static void triggerIn(uint16_t us) {
  68. TCNT0 = 0; // Reset Timer
  69. if (us <= (TIME_AFTER_OVERFLOW - 1)) {
  70. triggerState = COMPARE_MATCH;
  71. OCR0A = us * TIME_MULTIPLIER;
  72. } else {
  73. triggerState = OVERFLOW;
  74. triggerTimeRemaining = us - TIME_AFTER_OVERFLOW;
  75. }
  76. }
  77. static void nextState(void) {
  78. state++;
  79. if (state > MAX_STATES) {
  80. state = 0;
  81. delaySum = MIN_WAIT;
  82. }
  83. if ((state % 2) == 0) {
  84. // pulse pause
  85. CPPM_PORT &= ~(1 << CPPM_PIN);
  86. triggerIn(PULSE_LOW);
  87. } else {
  88. CPPM_PORT |= (1 << CPPM_PIN);
  89. if (state <= 15) {
  90. // normal ppm pulse
  91. uint8_t index = state / 2;
  92. triggerIn(cppmData[index]);
  93. delaySum += PULSE_WIDTH - cppmData[index];
  94. } else {
  95. // sync pulse
  96. triggerIn(delaySum);
  97. }
  98. }
  99. }
  100. ISR(TIM0_OVF_vect) {
  101. if (triggerState == OVERFLOW) {
  102. if (triggerTimeRemaining == 0) {
  103. triggerState = NONE;
  104. nextState();
  105. } else {
  106. triggerIn(triggerTimeRemaining);
  107. }
  108. }
  109. }
  110. ISR(TIM0_COMPA_vect) {
  111. if (triggerState == COMPARE_MATCH) {
  112. triggerState = NONE;
  113. nextState();
  114. }
  115. }