RCInput_PRU.cpp 2.0 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667
  1. #include <AP_HAL/AP_HAL.h>
  2. #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_PXF || \
  3. CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBOARD
  4. #include "RCInput_PRU.h"
  5. #include <errno.h>
  6. #include <fcntl.h>
  7. #include <poll.h>
  8. #include <stdint.h>
  9. #include <stdio.h>
  10. #include <stdlib.h>
  11. #include <string.h>
  12. #include <sys/mman.h>
  13. #include <sys/stat.h>
  14. #include <sys/time.h>
  15. #include <unistd.h>
  16. #include "GPIO.h"
  17. #define RCIN_PRUSS_SHAREDRAM_BASE 0x4a312000
  18. extern const AP_HAL::HAL& hal;
  19. using namespace Linux;
  20. void RCInput_PRU::init()
  21. {
  22. int mem_fd = open("/dev/mem", O_RDWR|O_SYNC|O_CLOEXEC);
  23. if (mem_fd == -1) {
  24. AP_HAL::panic("Unable to open /dev/mem");
  25. }
  26. ring_buffer = (volatile struct ring_buffer*) mmap(0, 0x1000, PROT_READ|PROT_WRITE,
  27. MAP_SHARED, mem_fd, RCIN_PRUSS_SHAREDRAM_BASE);
  28. close(mem_fd);
  29. ring_buffer->ring_head = 0;
  30. _s0_time = 0;
  31. // enable the spektrum RC input power
  32. hal.gpio->pinMode(BBB_P8_17, HAL_GPIO_OUTPUT);
  33. hal.gpio->write(BBB_P8_17, 1);
  34. }
  35. /*
  36. called at 1kHz to check for new pulse capture data from the PRU
  37. */
  38. void RCInput_PRU::_timer_tick()
  39. {
  40. while (ring_buffer->ring_head != ring_buffer->ring_tail) {
  41. if (ring_buffer->ring_tail >= NUM_RING_ENTRIES) {
  42. // invalid ring_tail from PRU - ignore RC input
  43. return;
  44. }
  45. if (ring_buffer->buffer[ring_buffer->ring_head].pin_value == 1) {
  46. // remember the time we spent in the low state
  47. _s0_time = ring_buffer->buffer[ring_buffer->ring_head].delta_t;
  48. } else {
  49. // the pulse value is the sum of the time spent in the low
  50. // and high states
  51. _process_rc_pulse(_s0_time, ring_buffer->buffer[ring_buffer->ring_head].delta_t);
  52. }
  53. // move to the next ring buffer entry
  54. ring_buffer->ring_head = (ring_buffer->ring_head + 1) % NUM_RING_ENTRIES;
  55. }
  56. }
  57. #endif // CONFIG_HAL_BOARD_SUBTYPE