RCOutput_PRU.cpp 2.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112
  1. #include "RCOutput_PRU.h"
  2. #include <dirent.h>
  3. #include <fcntl.h>
  4. #include <linux/spi/spidev.h>
  5. #include <signal.h>
  6. #include <stdint.h>
  7. #include <stdio.h>
  8. #include <stdlib.h>
  9. #include <sys/ioctl.h>
  10. #include <sys/mman.h>
  11. #include <sys/stat.h>
  12. #include <sys/types.h>
  13. #include <unistd.h>
  14. #include <AP_HAL/AP_HAL.h>
  15. using namespace Linux;
  16. #define PWM_CHAN_COUNT 12
  17. static const uint8_t chan_pru_map[]= {10,8,11,9,7,6,5,4,3,2,1,0}; //chan_pru_map[CHANNEL_NUM] = PRU_REG_R30/31_NUM;
  18. static void catch_sigbus(int sig)
  19. {
  20. AP_HAL::panic("RCOutput.cpp:SIGBUS error generated\n");
  21. }
  22. void RCOutput_PRU::init()
  23. {
  24. uint32_t mem_fd;
  25. signal(SIGBUS,catch_sigbus);
  26. mem_fd = open("/dev/mem", O_RDWR|O_SYNC|O_CLOEXEC);
  27. sharedMem_cmd = (struct pwm_cmd *) mmap(0, 0x1000, PROT_READ|PROT_WRITE,
  28. MAP_SHARED, mem_fd, RCOUT_PRUSS_SHAREDRAM_BASE);
  29. close(mem_fd);
  30. // all outputs default to 50Hz, the top level vehicle code
  31. // overrides this when necessary
  32. set_freq(0xFFFFFFFF, 50);
  33. }
  34. void RCOutput_PRU::set_freq(uint32_t chmask, uint16_t freq_hz) //LSB corresponds to CHAN_1
  35. {
  36. uint8_t i;
  37. unsigned long tick=TICK_PER_S/(unsigned long)freq_hz;
  38. for (i=0;i<PWM_CHAN_COUNT;i++) {
  39. if (chmask & (1U<<i)) {
  40. sharedMem_cmd->periodhi[chan_pru_map[i]][0]=tick;
  41. }
  42. }
  43. }
  44. uint16_t RCOutput_PRU::get_freq(uint8_t ch)
  45. {
  46. return TICK_PER_S/sharedMem_cmd->periodhi[chan_pru_map[ch]][0];
  47. }
  48. void RCOutput_PRU::enable_ch(uint8_t ch)
  49. {
  50. sharedMem_cmd->enmask |= 1U<<chan_pru_map[ch];
  51. }
  52. void RCOutput_PRU::disable_ch(uint8_t ch)
  53. {
  54. sharedMem_cmd->enmask &= !(1U<<chan_pru_map[ch]);
  55. }
  56. void RCOutput_PRU::write(uint8_t ch, uint16_t period_us)
  57. {
  58. if (corked) {
  59. pending[ch] = period_us;
  60. pending_mask |= (1U << ch);
  61. } else {
  62. sharedMem_cmd->periodhi[chan_pru_map[ch]][1] = TICK_PER_US*period_us;
  63. }
  64. }
  65. uint16_t RCOutput_PRU::read(uint8_t ch)
  66. {
  67. return (sharedMem_cmd->hilo_read[chan_pru_map[ch]][1]/TICK_PER_US);
  68. }
  69. void RCOutput_PRU::read(uint16_t* period_us, uint8_t len)
  70. {
  71. uint8_t i;
  72. if(len>PWM_CHAN_COUNT){
  73. len = PWM_CHAN_COUNT;
  74. }
  75. for(i=0;i<len;i++){
  76. period_us[i] = sharedMem_cmd->hilo_read[chan_pru_map[i]][1]/TICK_PER_US;
  77. }
  78. }
  79. void RCOutput_PRU::cork(void)
  80. {
  81. corked = true;
  82. }
  83. void RCOutput_PRU::push(void)
  84. {
  85. if (!corked) {
  86. return;
  87. }
  88. corked = false;
  89. for (uint8_t i=0; i<ARRAY_SIZE(pending); i++) {
  90. if (pending_mask & (1U << i)) {
  91. write(i, pending[i]);
  92. }
  93. }
  94. pending_mask = 0;
  95. }