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 2.5KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687
  1. /*
  2. * Combined-PPM signal generator
  3. *
  4. * Based on the code from:
  5. * https://quadmeup.com/generate-ppm-signal-with-arduino/
  6. * https://github.com/DzikuVx/ppm_encoder/blob/master/ppm_encoder_source.ino
  7. *
  8. * Copyright 2016 by Thomas Buck <xythobuz@xythobuz.de>
  9. *
  10. * This program is free software; you can redistribute it and/or
  11. * modify it under the terms of the GNU General Public License as
  12. * published by the Free Software Foundation, version 2.
  13. */
  14. #include <Arduino.h>
  15. #include "cppm.h"
  16. //#define DEBUG_OUTPUT
  17. #define CHANNELS 8 // set the number of chanels
  18. #define CHANNEL_DEFAULT_VALUE 1500 // set the default servo value
  19. #define FRAME_LENGTH 20000 // set the PPM frame length in microseconds (1ms = 1000µs)
  20. #define PULSE_LENGTH 100 // set the pulse length
  21. #define ON_STATE 1 // set polarity of the pulses: 1 is positive, 0 is negative
  22. static volatile uint16_t cppmData[CHANNELS];
  23. static volatile uint8_t state = 1;
  24. static volatile uint8_t currentChannel = CHANNELS;
  25. static volatile uint16_t calcRest = 0;
  26. void cppmInit(void) {
  27. #ifdef DEBUG_OUTPUT
  28. Serial.println("Initializing Timer...");
  29. #endif
  30. for (uint8_t i = 0; i < CHANNELS; i++) {
  31. cppmData[i] = CHANNEL_DEFAULT_VALUE;
  32. }
  33. pinMode(CPPM_OUTPUT_PIN, OUTPUT);
  34. digitalWrite(CPPM_OUTPUT_PIN, ON_STATE ? LOW : HIGH);
  35. cli();
  36. TCCR1A = 0; // set entire TCCR1 register to 0
  37. TCCR1B = 0;
  38. OCR1A = 100; // compare match register
  39. TCCR1B |= (1 << WGM12); // turn on CTC mode
  40. TCCR1B |= (1 << CS11); // 8 prescaler: 0,5 microseconds at 16mhz
  41. TIMSK1 |= (1 << OCIE1A); // enable timer compare interrupt
  42. sei();
  43. }
  44. void cppmCopy(uint16_t *data) {
  45. #ifdef DEBUG_OUTPUT
  46. Serial.println("New CPPM data!");
  47. #endif
  48. cli();
  49. for (int i = 0; i < CHANNELS; i++) {
  50. cppmData[i] = data[i];
  51. }
  52. sei();
  53. }
  54. ISR(TIMER1_COMPA_vect){
  55. TCNT1 = 0;
  56. if (state) {
  57. // start pulse
  58. digitalWrite(CPPM_OUTPUT_PIN, ON_STATE ? HIGH : LOW);
  59. OCR1A = PULSE_LENGTH << 1;
  60. state = 0;
  61. } else {
  62. // end pulse and calculate when to start the next pulse
  63. digitalWrite(CPPM_OUTPUT_PIN, ON_STATE ? LOW : HIGH);
  64. state = 1;
  65. if (currentChannel >= CHANNELS) {
  66. currentChannel = 0;
  67. calcRest += PULSE_LENGTH;
  68. OCR1A = (FRAME_LENGTH - calcRest) << 1;
  69. calcRest = 0;
  70. } else {
  71. OCR1A = (cppmData[currentChannel] - PULSE_LENGTH) << 1;
  72. calcRest += cppmData[currentChannel];
  73. currentChannel++;
  74. }
  75. }
  76. }