RCOutput_AioPRU.cpp 3.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157
  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 "RCOutput_AioPRU.h"
  12. #include <fcntl.h>
  13. #include <signal.h>
  14. #include <stdint.h>
  15. #include <stdio.h>
  16. #include <stdlib.h>
  17. #include <sys/mman.h>
  18. #include <unistd.h>
  19. #include <AP_HAL/AP_HAL.h>
  20. #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BLUE
  21. #include "../../Tools/Linux_HAL_Essentials/pru/aiopru/RcAioPRU_BBBLUE_bin.h"
  22. #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_POCKET
  23. #include "../../Tools/Linux_HAL_Essentials/pru/aiopru/RcAioPRU_POCKET_bin.h"
  24. #else
  25. #include "../../Tools/Linux_HAL_Essentials/pru/aiopru/RcAioPRU_BBBMINI_bin.h"
  26. #endif
  27. using namespace Linux;
  28. static void catch_sigbus(int sig)
  29. {
  30. AP_HAL::panic("RCOutputAioPRU.cpp:SIGBUS error generated\n");
  31. }
  32. void RCOutput_AioPRU::init()
  33. {
  34. uint32_t mem_fd;
  35. uint32_t *iram;
  36. uint32_t *ctrl;
  37. signal(SIGBUS,catch_sigbus);
  38. mem_fd = open("/dev/mem", O_RDWR|O_SYNC|O_CLOEXEC);
  39. pwm = (struct pwm*) mmap(0, 0x1000, PROT_READ|PROT_WRITE, MAP_SHARED, mem_fd, RCOUT_PRUSS_RAM_BASE);
  40. iram = (uint32_t*)mmap(0, 0x2000, PROT_READ|PROT_WRITE, MAP_SHARED, mem_fd, RCOUT_PRUSS_IRAM_BASE);
  41. ctrl = (uint32_t*)mmap(0, 0x1000, PROT_READ|PROT_WRITE, MAP_SHARED, mem_fd, RCOUT_PRUSS_CTRL_BASE);
  42. close(mem_fd);
  43. // Reset PRU
  44. *ctrl = 0;
  45. // Load firmware
  46. memcpy(iram, PRUcode, sizeof(PRUcode));
  47. // Start PRU
  48. *ctrl |= 2;
  49. // all outputs default to 50Hz, the top level vehicle code
  50. // overrides this when necessary
  51. set_freq(0xFFFFFFFF, 50);
  52. }
  53. void RCOutput_AioPRU::set_freq(uint32_t chmask, uint16_t freq_hz)
  54. {
  55. uint8_t i;
  56. uint32_t tick = TICK_PER_S / freq_hz;
  57. for(i = 0; i < PWM_CHAN_COUNT; i++) {
  58. if(chmask & (1U << i)) {
  59. pwm->channel[i].time_t = tick;
  60. }
  61. }
  62. }
  63. uint16_t RCOutput_AioPRU::get_freq(uint8_t ch)
  64. {
  65. uint16_t ret = 0;
  66. if(ch < PWM_CHAN_COUNT) {
  67. ret = TICK_PER_S / pwm->channel[ch].time_t;
  68. }
  69. return ret;
  70. }
  71. void RCOutput_AioPRU::enable_ch(uint8_t ch)
  72. {
  73. if(ch < PWM_CHAN_COUNT) {
  74. pwm->channelenable |= 1U << ch;
  75. }
  76. }
  77. void RCOutput_AioPRU::disable_ch(uint8_t ch)
  78. {
  79. if(ch < PWM_CHAN_COUNT) {
  80. pwm->channelenable &= !(1U << ch);
  81. }
  82. }
  83. void RCOutput_AioPRU::write(uint8_t ch, uint16_t period_us)
  84. {
  85. if(ch < PWM_CHAN_COUNT) {
  86. if (corked) {
  87. pending_mask |= (1U << ch);
  88. pending[ch] = period_us;
  89. } else {
  90. pwm->channel[ch].time_high = TICK_PER_US * period_us;
  91. }
  92. }
  93. }
  94. uint16_t RCOutput_AioPRU::read(uint8_t ch)
  95. {
  96. uint16_t ret = 0;
  97. if(ch < PWM_CHAN_COUNT) {
  98. ret = (pwm->channel[ch].time_high / TICK_PER_US);
  99. }
  100. return ret;
  101. }
  102. void RCOutput_AioPRU::read(uint16_t* period_us, uint8_t len)
  103. {
  104. uint8_t i;
  105. if(len > PWM_CHAN_COUNT) {
  106. len = PWM_CHAN_COUNT;
  107. }
  108. for(i = 0; i < len; i++) {
  109. period_us[i] = pwm->channel[i].time_high / TICK_PER_US;
  110. }
  111. }
  112. void RCOutput_AioPRU::cork(void)
  113. {
  114. corked = true;
  115. }
  116. void RCOutput_AioPRU::push(void)
  117. {
  118. if (!corked) {
  119. return;
  120. }
  121. corked = false;
  122. for (uint8_t i=0; i<PWM_CHAN_COUNT; i++) {
  123. if (pending_mask & (1U<<i)) {
  124. write(i, pending[i]);
  125. }
  126. }
  127. pending_mask = 0;
  128. }