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.6KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394
  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 Serial
  17. CPPM* CPPM::inst = NULL;
  18. void CPPM::init(void) {
  19. #ifdef DEBUG_OUTPUT
  20. DEBUG_OUTPUT.println("Initializing Timer...");
  21. #endif
  22. state = 1;
  23. currentChannel = channels;
  24. calcRest = 0;
  25. for (uint8_t i = 0; i < channels; i++) {
  26. data[i] = CHANNEL_DEFAULT_VALUE;
  27. }
  28. pinMode(output, OUTPUT);
  29. digitalWrite(output, CPPM::inst->onState ? LOW : HIGH);
  30. cli();
  31. TCCR1A = 0; // set entire TCCR1 register to 0
  32. TCCR1B = 0;
  33. OCR1A = 100; // compare match register
  34. TCCR1B |= (1 << WGM12); // turn on CTC mode
  35. TCCR1B |= (1 << CS11); // 8 prescaler: 0,5 microseconds at 16mhz
  36. TIMSK1 |= (1 << OCIE1A); // enable timer compare interrupt
  37. sei();
  38. }
  39. void CPPM::setOutput(uint8_t i) {
  40. digitalWrite(output, LOW);
  41. pinMode(output, INPUT);
  42. output = i;
  43. pinMode(output, OUTPUT);
  44. digitalWrite(output, CPPM::inst->onState ? LOW : HIGH);
  45. }
  46. void CPPM::copy(uint16_t* d) {
  47. #ifdef DEBUG_OUTPUT
  48. DEBUG_OUTPUT.println("New CPPM data!");
  49. #endif
  50. cli();
  51. for (int i = 0; i < channels; i++) {
  52. data[i] = d[i];
  53. }
  54. sei();
  55. }
  56. ISR(TIMER1_COMPA_vect) {
  57. if (!CPPM::inst) {
  58. return;
  59. }
  60. TCNT1 = 0;
  61. if (CPPM::inst->state) {
  62. // start pulse
  63. digitalWrite(CPPM::inst->output, CPPM::inst->onState ? HIGH : LOW);
  64. OCR1A = CPPM::inst->pulseLength << 1;
  65. CPPM::inst->state = 0;
  66. } else {
  67. // end pulse and calculate when to start the next pulse
  68. digitalWrite(CPPM::inst->output, CPPM::inst->onState ? LOW : HIGH);
  69. CPPM::inst->state = 1;
  70. if (CPPM::inst->currentChannel >= CPPM::inst->channels) {
  71. CPPM::inst->currentChannel = 0;
  72. CPPM::inst->calcRest += CPPM::inst->pulseLength;
  73. OCR1A = (CPPM::inst->frameLength - CPPM::inst->calcRest) << 1;
  74. CPPM::inst->calcRest = 0;
  75. } else {
  76. OCR1A = (CPPM::inst->data[CPPM::inst->currentChannel] - CPPM::inst->pulseLength) << 1;
  77. CPPM::inst->calcRest += CPPM::inst->data[CPPM::inst->currentChannel];
  78. CPPM::inst->currentChannel++;
  79. }
  80. }
  81. }