Control drones with a proper joystick
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.7KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150
  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. * Copyright 2016 by Thomas Buck <xythobuz@xythobuz.de>
  26. *
  27. * This program is free software; you can redistribute it and/or
  28. * modify it under the terms of the GNU General Public License as
  29. * published by the Free Software Foundation, version 2.
  30. */
  31. #include <avr/io.h>
  32. #include <avr/interrupt.h>
  33. #include "cppm.h"
  34. #define MAX_STATES 17
  35. #define CHANNELS 8
  36. #define WHOLE_PULSE_WIDTH 20000
  37. #define PULSE_WIDTH 2000
  38. #define MAX_PULSE_WIDTH (CHANNELS * PULSE_WIDTH) // 16.000
  39. #define PULSE_LOW 100
  40. #define PULSE_LOW_SUM ((CHANNELS + 1) * PULSE_LOW) // 900
  41. #define MIN_WAIT (WHOLE_PULSE_WIDTH - MAX_PULSE_WIDTH - PULSE_LOW_SUM) // 3100
  42. #define TIME_AFTER_OVERFLOW 128
  43. #define TIME_MULTIPLIER 2
  44. volatile uint16_t cppmData[CHANNELS] = { 1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500 };
  45. volatile uint16_t delaySum = 0;
  46. volatile uint8_t state = 0;
  47. volatile uint16_t triggerTimeRemaining = 0;
  48. #define NONE 0
  49. #define COMPARE_MATCH 1
  50. #define OVERFLOW 2
  51. volatile uint8_t triggerState = NONE;
  52. static void triggerIn(uint16_t us);
  53. static void nextState(void);
  54. void cppmInit(void) {
  55. // Set pin to output mode
  56. CPPM_DDR |= (1 << CPPM_PIN);
  57. // Start with a low pulse
  58. CPPM_PORT &= ~(1 << CPPM_PIN);
  59. TCCR0B |= (1 << CS01); // Prescaler: 8
  60. #ifdef DEBUG
  61. TIMSK0 |= (1 << TOIE0) | (1 << OCIE0A); // Enable Overflow and Compare Match Interrupt
  62. #else
  63. TIMSK |= (1 << TOIE0) | (1 << OCIE0A); // Enable Overflow and Compare Match Interrupt
  64. #endif
  65. OCR0A = 0;
  66. state = 0;
  67. delaySum = MIN_WAIT;
  68. triggerIn(PULSE_LOW);
  69. }
  70. void cppmCopy(uint16_t *data) {
  71. cli();
  72. for (int i = 0; i < CHANNELS; i++) {
  73. cppmData[i] = data[i];
  74. }
  75. sei();
  76. }
  77. static void triggerIn(uint16_t us) {
  78. TCNT0 = 0; // Reset Timer
  79. if (us <= (TIME_AFTER_OVERFLOW - 1)) {
  80. triggerState = COMPARE_MATCH;
  81. OCR0A = us * TIME_MULTIPLIER;
  82. } else {
  83. triggerState = OVERFLOW;
  84. triggerTimeRemaining = us - TIME_AFTER_OVERFLOW;
  85. }
  86. }
  87. static void nextState(void) {
  88. state++;
  89. if (state > MAX_STATES) {
  90. state = 0;
  91. delaySum = MIN_WAIT;
  92. }
  93. if ((state % 2) == 0) {
  94. // pulse pause
  95. CPPM_PORT &= ~(1 << CPPM_PIN);
  96. triggerIn(PULSE_LOW);
  97. } else {
  98. CPPM_PORT |= (1 << CPPM_PIN);
  99. if (state <= 15) {
  100. // normal ppm pulse
  101. uint8_t index = state / 2;
  102. triggerIn(cppmData[index]);
  103. delaySum += PULSE_WIDTH - cppmData[index];
  104. } else {
  105. // sync pulse
  106. triggerIn(delaySum);
  107. }
  108. }
  109. }
  110. #ifdef DEBUG
  111. ISR(TIMER0_OVF_vect) {
  112. #else
  113. ISR(TIM0_OVF_vect) {
  114. #endif
  115. if (triggerState == OVERFLOW) {
  116. if (triggerTimeRemaining == 0) {
  117. triggerState = NONE;
  118. nextState();
  119. } else {
  120. triggerIn(triggerTimeRemaining);
  121. }
  122. }
  123. }
  124. #ifdef DEBUG
  125. ISR(TIMER0_COMPA_vect) {
  126. #else
  127. ISR(TIM0_COMPA_vect) {
  128. #endif
  129. if (triggerState == COMPARE_MATCH) {
  130. triggerState = NONE;
  131. nextState();
  132. }
  133. }