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.cpp 3.0KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115
  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 <TimerOne.h>
  32. #include "cppm.h"
  33. //#define DEBUG_OUTPUT
  34. //#define DEBUG_OUTPUT_ALL
  35. #define CHANNELS 8
  36. #define MAX_STATES ((2 * CHANNELS) + 1)
  37. #define WHOLE_PULSE_WIDTH 20000
  38. #define PULSE_WIDTH 2000
  39. #define MAX_PULSE_WIDTH (CHANNELS * PULSE_WIDTH) // 16.000
  40. #define PULSE_LOW 100
  41. #define PULSE_LOW_SUM ((CHANNELS + 1) * PULSE_LOW) // 900
  42. #define MIN_WAIT (WHOLE_PULSE_WIDTH - MAX_PULSE_WIDTH - PULSE_LOW_SUM) // 3100
  43. #define TIME_AFTER_OVERFLOW 128
  44. #define TIME_MULTIPLIER 2
  45. volatile uint16_t cppmData[CHANNELS] = { 1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500 };
  46. volatile uint16_t delaySum = 0;
  47. volatile uint8_t state = 0;
  48. static void triggerIn(uint16_t us);
  49. static void nextState(void);
  50. void cppmInit(void) {
  51. #ifdef DEBUG_OUTPUT
  52. Serial.println("Initializing Timer...");
  53. #endif
  54. pinMode(CPPM_OUTPUT_PIN, OUTPUT);
  55. digitalWrite(CPPM_OUTPUT_PIN, LOW);
  56. Timer1.initialize(PULSE_LOW);
  57. Timer1.attachInterrupt(&nextState);
  58. state = 0;
  59. delaySum = MIN_WAIT;
  60. }
  61. void cppmCopy(uint16_t *data) {
  62. #ifdef DEBUG_OUTPUT
  63. Serial.println("New CPPM data!");
  64. #endif
  65. cli();
  66. for (int i = 0; i < CHANNELS; i++) {
  67. cppmData[i] = data[i];
  68. }
  69. sei();
  70. }
  71. static void triggerIn(uint16_t us) {
  72. Timer1.setPeriod(us);
  73. //Timer1.start();
  74. }
  75. static void nextState(void) {
  76. //Timer1.stop();
  77. #ifdef DEBUG_OUTPUT_ALL
  78. Serial.print("CPPM state ");
  79. Serial.println(state, DEC);
  80. #endif
  81. state++;
  82. if (state > MAX_STATES) {
  83. state = 0;
  84. delaySum = MIN_WAIT;
  85. }
  86. if (!(state & 0x01)) {
  87. // pulse pause
  88. digitalWrite(CPPM_OUTPUT_PIN, LOW);
  89. triggerIn(PULSE_LOW);
  90. } else {
  91. digitalWrite(CPPM_OUTPUT_PIN, HIGH);
  92. if (state <= 15) {
  93. // normal ppm pulse
  94. uint8_t index = state >> 1;
  95. triggerIn(cppmData[index]);
  96. delaySum += PULSE_WIDTH - cppmData[index];
  97. } else {
  98. // sync pulse
  99. triggerIn(delaySum);
  100. }
  101. }
  102. }