RCInput_AioPRU.cpp 2.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566
  1. // This program is free software: you can redistribute it and/or modify
  2. // it under the terms of the GNU General Public License as published by
  3. // the Free Software Foundation, either version 3 of the License, or
  4. // (at your option) any later version.
  5. // This program is distributed in the hope that it will be useful,
  6. // but WITHOUT ANY WARRANTY; without even the implied warranty of
  7. // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  8. // GNU General Public License for more details.
  9. // You should have received a copy of the GNU General Public License
  10. // along with this program. If not, see <http://www.gnu.org/licenses/>.
  11. #include <AP_HAL/AP_HAL.h>
  12. #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BBBMINI || \
  13. CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BLUE || \
  14. CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_POCKET
  15. #include <errno.h>
  16. #include <fcntl.h>
  17. #include <poll.h>
  18. #include <stdint.h>
  19. #include <stdio.h>
  20. #include <stdlib.h>
  21. #include <string.h>
  22. #include <sys/mman.h>
  23. #include <sys/stat.h>
  24. #include <sys/time.h>
  25. #include <unistd.h>
  26. #include "RCInput.h"
  27. #include "RCInput_AioPRU.h"
  28. extern const AP_HAL::HAL& hal;
  29. using namespace Linux;
  30. void RCInput_AioPRU::init()
  31. {
  32. int mem_fd = open("/dev/mem", O_RDWR|O_SYNC|O_CLOEXEC);
  33. if (mem_fd == -1) {
  34. AP_HAL::panic("Unable to open /dev/mem");
  35. }
  36. ring_buffer = (volatile struct ring_buffer*) mmap(0, 0x1000, PROT_READ|PROT_WRITE, MAP_SHARED, mem_fd, RCIN_PRUSS_RAM_BASE);
  37. close(mem_fd);
  38. ring_buffer->ring_head = 0;
  39. }
  40. /*
  41. called at 1kHz to check for new pulse capture data from the PRU
  42. */
  43. void RCInput_AioPRU::_timer_tick()
  44. {
  45. while (ring_buffer->ring_head != ring_buffer->ring_tail) {
  46. if (ring_buffer->ring_tail >= NUM_RING_ENTRIES) {
  47. // invalid ring_tail from PRU - ignore RC input
  48. return;
  49. }
  50. _process_rc_pulse((ring_buffer->buffer[ring_buffer->ring_head].s1_t) / TICK_PER_US,
  51. (ring_buffer->buffer[ring_buffer->ring_head].s0_t) / TICK_PER_US);
  52. // move to the next ring buffer entry
  53. ring_buffer->ring_head = (ring_buffer->ring_head + 1) % NUM_RING_ENTRIES;
  54. }
  55. }
  56. #endif // CONFIG_HAL_BOARD_SUBTYPE