RCOutput_Disco.cpp 2.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116
  1. /*
  2. * Copyright (C) 2016 Andrew Tridgell. All rights reserved.
  3. *
  4. * This file is free software: you can redistribute it and/or modify it
  5. * under the terms of the GNU General Public License as published by the
  6. * Free Software Foundation, either version 3 of the License, or
  7. * (at your option) any later version.
  8. *
  9. * This file is distributed in the hope that it will be useful, but
  10. * WITHOUT ANY WARRANTY; without even the implied warranty of
  11. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
  12. * See the GNU General Public License for more details.
  13. *
  14. * You should have received a copy of the GNU General Public License along
  15. * with this program. If not, see <http://www.gnu.org/licenses/>.
  16. */
  17. /*
  18. RCOutput on the Disco combines I2C motor output (for channel 3) with
  19. PWM output for the other channels. This class is a wrapper around
  20. the two other classes
  21. */
  22. #include "RCOutput_Disco.h"
  23. #include <AP_HAL/AP_HAL.h>
  24. #include <stdio.h>
  25. namespace Linux {
  26. RCOutput_Disco::RCOutput_Disco(AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
  27. : bebop_out(std::move(dev))
  28. {
  29. }
  30. void RCOutput_Disco::init()
  31. {
  32. sysfs_out.init();
  33. bebop_out.init();
  34. printf("RCOutput_Disco: initialised\n");
  35. }
  36. void RCOutput_Disco::set_freq(uint32_t chmask, uint16_t freq_hz)
  37. {
  38. for (uint8_t i = 0; i < ARRAY_SIZE(output_table); i++) {
  39. if (chmask & (1U << i)) {
  40. output_table[i].output.set_freq(1U<<output_table[i].channel, freq_hz);
  41. }
  42. }
  43. }
  44. uint16_t RCOutput_Disco::get_freq(uint8_t ch)
  45. {
  46. if (ch >= ARRAY_SIZE(output_table)) {
  47. return 0;
  48. }
  49. return output_table[ch].output.get_freq(output_table[ch].channel);
  50. }
  51. void RCOutput_Disco::enable_ch(uint8_t ch)
  52. {
  53. if (ch >= ARRAY_SIZE(output_table)) {
  54. return;
  55. }
  56. output_table[ch].output.enable_ch(output_table[ch].channel);
  57. }
  58. void RCOutput_Disco::disable_ch(uint8_t ch)
  59. {
  60. if (ch >= ARRAY_SIZE(output_table)) {
  61. return;
  62. }
  63. output_table[ch].output.disable_ch(output_table[ch].channel);
  64. }
  65. void RCOutput_Disco::write(uint8_t ch, uint16_t period_us)
  66. {
  67. if (ch >= ARRAY_SIZE(output_table)) {
  68. return;
  69. }
  70. output_table[ch].output.write(output_table[ch].channel, period_us);
  71. }
  72. uint16_t RCOutput_Disco::read(uint8_t ch)
  73. {
  74. if (ch >= ARRAY_SIZE(output_table)) {
  75. return 0;
  76. }
  77. return output_table[ch].output.read(output_table[ch].channel);
  78. }
  79. void RCOutput_Disco::read(uint16_t *period_us, uint8_t len)
  80. {
  81. for (int i = 0; i < len; i++) {
  82. period_us[i] = read(i);
  83. }
  84. }
  85. void RCOutput_Disco::cork(void)
  86. {
  87. sysfs_out.cork();
  88. bebop_out.cork();
  89. }
  90. void RCOutput_Disco::push(void)
  91. {
  92. sysfs_out.push();
  93. bebop_out.push();
  94. }
  95. void RCOutput_Disco::set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm)
  96. {
  97. sysfs_out.set_esc_scaling(min_pwm, max_pwm);
  98. bebop_out.set_esc_scaling(min_pwm, max_pwm);
  99. }
  100. }