Control drones with a proper joystick
您最多选择25个主题 主题必须以字母或数字开头,可以包含连字符 (-),并且长度不得超过35个字符

cppm.h 1.9KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172
  1. /*
  2. * Combined-PPM signal generator
  3. * Copyright 2016 by Thomas Buck <xythobuz@xythobuz.de>
  4. *
  5. * This program is free software; you can redistribute it and/or
  6. * modify it under the terms of the GNU General Public License as
  7. * published by the Free Software Foundation, version 2.
  8. */
  9. #ifndef __CPPM_H__
  10. #define __CPPM_H__
  11. #include <stdint.h>
  12. #include <avr/interrupt.h>
  13. #include "config.h"
  14. ISR(TIMER1_COMPA_vect);
  15. class CPPM {
  16. public:
  17. inline static CPPM& instance() {
  18. if (!inst) {
  19. inst = new CPPM();
  20. }
  21. return *inst;
  22. }
  23. void init(void);
  24. void copy(uint16_t* d);
  25. inline uint16_t getChannels() { return channels; }
  26. inline void setChannels(uint16_t c) {
  27. if (c > CHANNELS_MAX)
  28. c = CHANNELS_MAX;
  29. channels = c;
  30. }
  31. inline uint16_t getFrameLength() { return frameLength; }
  32. inline void setFrameLength(uint16_t fl) { frameLength = fl; }
  33. inline uint16_t getPulseLength() { return pulseLength; }
  34. inline void setPulseLength(uint16_t pl) { pulseLength = pl; }
  35. inline uint8_t getInvert() { return !onState; }
  36. inline void setInvert(uint8_t i) { onState = !i; }
  37. inline uint8_t getOutput() { return output; }
  38. void setOutput(uint8_t i);
  39. private:
  40. CPPM() : channels(DEFAULT_CHANNELS), frameLength(DEFAULT_FRAME_LENGTH),
  41. pulseLength(DEFAULT_PULSE_LENGTH), onState(!DEFAULT_INVERT_STATE),
  42. output(CPPM_OUTPUT_PIN_DEFAULT) { }
  43. CPPM(CPPM&) { }
  44. volatile uint16_t channels;
  45. volatile uint16_t frameLength; // PPM frame length in microseconds (1ms = 1000µs)
  46. volatile uint16_t pulseLength;
  47. volatile uint8_t onState; // polarity of the pulses: 1 is positive, 0 is negative
  48. volatile uint8_t output;
  49. volatile uint16_t data[CHANNELS_MAX];
  50. volatile uint8_t state;
  51. volatile uint8_t currentChannel;
  52. volatile uint16_t calcRest;
  53. static CPPM* inst;
  54. friend void TIMER1_COMPA_vect(void);
  55. };
  56. #endif // __CPPM_H__