RCOutput_ZYNQ.cpp 3.0 KB

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