Нет описания
Вы не можете выбрать более 25 тем Темы должны начинаться с буквы или цифры, могут содержать дефисы(-) и должны содержать не более 35 символов.

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137
  1. /* Arduino library for decoding PPM receiver signal
  2. *
  3. * Copyright (c) 2020 Victor Glekler
  4. *
  5. * MIT License
  6. * Permission is hereby granted, free of charge, to any person obtaining a copy
  7. * of this software and associated documentation files (the "Software"), to deal
  8. * in the Software without restriction, including without limitation the rights
  9. * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
  10. * copies of the Software, and to permit persons to whom the Software is
  11. * furnished to do so, subject to the following conditions:
  12. *
  13. * The above copyright notice and this permission notice shall be included in all
  14. * copies or substantial portions of the Software.
  15. *
  16. * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
  17. * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
  18. * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
  19. * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
  20. * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
  21. * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
  22. * SOFTWARE.
  23. */
  24. #include "PPM.h"
  25. #include <avr/interrupt.h>
  26. #include <avr/io.h>
  27. PPM ppm;
  28. ISR(INT1_vect)
  29. {
  30. //PORTB ^= (1 << PB5);
  31. ppm.process();
  32. }
  33. ISR(TIMER2_OVF_vect)
  34. {
  35. ppm.increment_ovf_count();
  36. }
  37. void PPM::begin(uint8_t max_channels = MAX_CHANNELS)
  38. {
  39. //pinMode(inputPort, INPUT);
  40. //pinMode(3, INPUT);
  41. pinMode(3, INPUT_PULLUP);
  42. //attachInterrupt(digitalPinToInterrupt(inputPort), ISR_PPM, FALLING);
  43. cli();
  44. // D3 / PD3 / INT1 for PPM input hard-coded
  45. EICRA &= ~((1 << ISC11) | (1 << ISC10));
  46. EICRA |= (1 << ISC11); // falling
  47. //EICRA |= (1 << ISC11) | (1 << ISC10); // rising
  48. EIMSK |= (1 << INT1);
  49. _max_channels = max_channels;
  50. for (uint8_t i = 0; i < MAX_CHANNELS; i++)
  51. _channels[i] = 0;
  52. _ovf_count = 0;
  53. _micros_count = 0;
  54. TCCR2B = (TCCR2B & 0b11111000) | (1 << CS21); // 8 prescaler
  55. TIMSK2 |= 0b00000001; // enable TIMER2 overflow interrupt
  56. TCCR2A &= 0b11111100;
  57. TCCR2B &= 0b11110111;
  58. sei();
  59. }
  60. uint32_t PPM::_micros()
  61. {
  62. uint8_t SREG_old = SREG;
  63. cli();
  64. uint8_t tcnt2 = TCNT2;
  65. bool flag_save = bitRead(TIFR2, 0);
  66. if (flag_save)
  67. {
  68. tcnt2 = TCNT2;
  69. _ovf_count++;
  70. TIFR2 |= 0b00000001;
  71. }
  72. _micros_count = (_ovf_count << 8) | tcnt2 ;
  73. SREG = SREG_old;
  74. #if (F_CPU == 16000000)
  75. return _micros_count >> 1;
  76. #elif (F_CPU == 8000000)
  77. return _micros_count;
  78. #endif
  79. }
  80. void PPM::increment_ovf_count()
  81. {
  82. _ovf_count++;
  83. }
  84. void PPM::process()
  85. {
  86. static uint8_t _channel_index = _max_channels;
  87. static uint32_t _lastTime = 0, _currentTime = 0;
  88. _currentTime = _micros();
  89. int16_t pulse_us = _currentTime - _lastTime;
  90. _lastTime = _currentTime;
  91. if (pulse_us > 3000 && pulse_us < 12000) // sync
  92. {
  93. _channel_index = 0;
  94. _available = true;
  95. return;
  96. }
  97. else if (pulse_us > 12000)
  98. _available = false;
  99. if (_channel_index < _max_channels)
  100. _channels[_channel_index++] = constrain(pulse_us, MIN_PULSE, MAX_PULSE);
  101. }
  102. uint16_t PPM::get(uint8_t channel)
  103. {
  104. return (_channels[channel - 1]);
  105. }
  106. uint8_t PPM::getPWM(uint8_t channel)
  107. {
  108. return (_channels[channel - 1] - MIN_PULSE) * 0.255f;
  109. }
  110. uint16_t PPM::getServo_us(uint8_t channel){
  111. return ( (_channels[channel - 1] - 706.89655) * 1.856 ); // range 0 -> 180 using WriteMicroseconds
  112. }
  113. bool PPM::available()
  114. {
  115. return _available;
  116. }