PWM_Sysfs.cpp 8.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287
  1. /*
  2. * Copyright (C) 2015 Intel Corporation. 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. #include "PWM_Sysfs.h"
  18. #include <errno.h>
  19. #include <fcntl.h>
  20. #include <inttypes.h>
  21. #include <stdio.h>
  22. #include <stdlib.h>
  23. #include <unistd.h>
  24. #include <AP_HAL/AP_HAL.h>
  25. #include <AP_Math/AP_Math.h>
  26. static const AP_HAL::HAL &hal = AP_HAL::get_HAL();
  27. namespace Linux {
  28. PWM_Sysfs_Base::PWM_Sysfs_Base(char* export_path, char* polarity_path,
  29. char* enable_path, char* duty_path,
  30. char* period_path, uint8_t channel)
  31. : _export_path(export_path)
  32. , _polarity_path(polarity_path)
  33. , _enable_path(enable_path)
  34. , _duty_path(duty_path)
  35. , _period_path(period_path)
  36. , _channel(channel)
  37. {
  38. }
  39. PWM_Sysfs_Base::~PWM_Sysfs_Base()
  40. {
  41. ::close(_duty_cycle_fd);
  42. free(_polarity_path);
  43. free(_enable_path);
  44. free(_period_path);
  45. }
  46. void PWM_Sysfs_Base::init()
  47. {
  48. if (_export_path == nullptr || _enable_path == nullptr ||
  49. _period_path == nullptr || _duty_path == nullptr) {
  50. AP_HAL::panic("PWM_Sysfs: export=%p enable=%p period=%p duty=%p"
  51. " required path is NULL", _export_path, _enable_path,
  52. _period_path, _duty_path);
  53. }
  54. /* Not checking the return of write_file since it will fail if
  55. * the pwm has already been exported
  56. */
  57. Util::from(hal.util)->write_file(_export_path, "%u", _channel);
  58. free(_export_path);
  59. _duty_cycle_fd = ::open(_duty_path, O_RDWR | O_CLOEXEC);
  60. if (_duty_cycle_fd < 0) {
  61. AP_HAL::panic("LinuxPWM_Sysfs:Unable to open file %s: %s",
  62. _duty_path, strerror(errno));
  63. }
  64. free(_duty_path);
  65. }
  66. void PWM_Sysfs_Base::enable(bool value)
  67. {
  68. if (Util::from(hal.util)->write_file(_enable_path, "%u", value) < 0) {
  69. hal.console->printf("LinuxPWM_Sysfs: %s Unable to %s\n",
  70. _enable_path, value ? "enable" : "disable");
  71. }
  72. }
  73. bool PWM_Sysfs_Base::is_enabled()
  74. {
  75. unsigned int enabled;
  76. if (Util::from(hal.util)->read_file(_enable_path, "%u", &enabled) < 0) {
  77. hal.console->printf("LinuxPWM_Sysfs: %s Unable to get status\n",
  78. _enable_path);
  79. }
  80. return enabled;
  81. }
  82. void PWM_Sysfs_Base::set_period(uint32_t nsec_period)
  83. {
  84. set_duty_cycle(0);
  85. if (Util::from(hal.util)->write_file(_period_path, "%u", nsec_period) < 0) {
  86. hal.console->printf("LinuxPWM_Sysfs: %s Unable to set period\n",
  87. _period_path);
  88. }
  89. }
  90. uint32_t PWM_Sysfs_Base::get_period()
  91. {
  92. uint32_t nsec_period;
  93. if (Util::from(hal.util)->read_file(_period_path, "%u", &nsec_period) < 0) {
  94. hal.console->printf("LinuxPWM_Sysfs: %s Unable to get period\n",
  95. _period_path);
  96. nsec_period = 0;
  97. }
  98. return nsec_period;
  99. }
  100. void PWM_Sysfs_Base::set_freq(uint32_t freq)
  101. {
  102. set_period(hz_to_nsec(freq));
  103. }
  104. uint32_t PWM_Sysfs_Base::get_freq()
  105. {
  106. return nsec_to_hz(get_period());
  107. }
  108. bool PWM_Sysfs_Base::set_duty_cycle(uint32_t nsec_duty_cycle)
  109. {
  110. /* Don't log fails since this could spam the console */
  111. if (dprintf(_duty_cycle_fd, "%u", nsec_duty_cycle) < 0) {
  112. return false;
  113. }
  114. _nsec_duty_cycle_value = nsec_duty_cycle;
  115. return true;
  116. }
  117. uint32_t PWM_Sysfs_Base::get_duty_cycle()
  118. {
  119. return _nsec_duty_cycle_value;
  120. }
  121. void PWM_Sysfs_Base::set_polarity(PWM_Sysfs_Base::Polarity polarity)
  122. {
  123. if (Util::from(hal.util)->write_file(_polarity_path, "%s",
  124. polarity == NORMAL ?
  125. "normal" : "inversed") < 0) {
  126. hal.console->printf("LinuxPWM_Sysfs: %s Unable to set polarity\n",
  127. _polarity_path);
  128. }
  129. }
  130. PWM_Sysfs_Base::Polarity PWM_Sysfs_Base::get_polarity()
  131. {
  132. char polarity[16];
  133. if (Util::from(hal.util)->read_file(_polarity_path, "%s", polarity) < 0) {
  134. hal.console->printf("LinuxPWM_Sysfs: %s Unable to get polarity\n",
  135. _polarity_path);
  136. return NORMAL;
  137. }
  138. return strncmp(polarity, "normal", sizeof(polarity)) ? INVERSE : NORMAL;
  139. }
  140. /* PWM Sysfs api for mainline kernel */
  141. char *PWM_Sysfs::_generate_export_path(uint8_t chip)
  142. {
  143. char *path;
  144. int r = asprintf(&path, "/sys/class/pwm/pwmchip%u/export", chip);
  145. if (r == -1) {
  146. AP_HAL::panic("LinuxPWM_Sysfs :"
  147. "couldn't allocate export path\n");
  148. }
  149. return path;
  150. }
  151. char *PWM_Sysfs::_generate_polarity_path(uint8_t chip, uint8_t channel)
  152. {
  153. char *path;
  154. int r = asprintf(&path, "/sys/class/pwm/pwmchip%u/pwm%u/polarity",
  155. chip, channel);
  156. if (r == -1) {
  157. AP_HAL::panic("LinuxPWM_Sysfs :"
  158. "couldn't allocate polarity path\n");
  159. }
  160. return path;
  161. }
  162. char *PWM_Sysfs::_generate_enable_path(uint8_t chip, uint8_t channel)
  163. {
  164. char *path;
  165. int r = asprintf(&path, "/sys/class/pwm/pwmchip%u/pwm%u/enable",
  166. chip, channel);
  167. if (r == -1) {
  168. AP_HAL::panic("LinuxPWM_Sysfs :"
  169. "couldn't allocate enable path\n");
  170. }
  171. return path;
  172. }
  173. char *PWM_Sysfs::_generate_duty_path(uint8_t chip, uint8_t channel)
  174. {
  175. char *path;
  176. int r = asprintf(&path, "/sys/class/pwm/pwmchip%u/pwm%u/duty_cycle",
  177. chip, channel);
  178. if (r == -1) {
  179. AP_HAL::panic("LinuxPWM_Sysfs :"
  180. "couldn't allocate duty path\n");
  181. }
  182. return path;
  183. }
  184. char *PWM_Sysfs::_generate_period_path(uint8_t chip, uint8_t channel)
  185. {
  186. char *path;
  187. int r = asprintf(&path, "/sys/class/pwm/pwmchip%u/pwm%u/period",
  188. chip, channel);
  189. if (r == -1) {
  190. AP_HAL::panic("LinuxPWM_Sysfs :"
  191. "couldn't allocate period path\n");
  192. }
  193. return path;
  194. }
  195. PWM_Sysfs::PWM_Sysfs(uint8_t chip, uint8_t channel) :
  196. PWM_Sysfs_Base(_generate_export_path(chip),
  197. _generate_polarity_path(chip, channel),
  198. _generate_enable_path(chip, channel),
  199. _generate_duty_path(chip, channel),
  200. _generate_period_path(chip, channel),
  201. channel)
  202. {
  203. }
  204. /* PWM Sysfs api for bebop kernel */
  205. char *PWM_Sysfs_Bebop::_generate_export_path()
  206. {
  207. return strdup("/sys/class/pwm/export");
  208. }
  209. char *PWM_Sysfs_Bebop::_generate_enable_path(uint8_t channel)
  210. {
  211. char *path;
  212. int r = asprintf(&path, "/sys/class/pwm/pwm_%u/run",
  213. channel);
  214. if (r == -1) {
  215. AP_HAL::panic("LinuxPWM_Sysfs :"
  216. "couldn't allocate enable path\n");
  217. }
  218. return path;
  219. }
  220. char *PWM_Sysfs_Bebop::_generate_duty_path(uint8_t channel)
  221. {
  222. char *path;
  223. int r = asprintf(&path, "/sys/class/pwm/pwm_%u/duty_ns",
  224. channel);
  225. if (r == -1) {
  226. AP_HAL::panic("LinuxPWM_Sysfs :"
  227. "couldn't allocate duty path\n");
  228. }
  229. return path;
  230. }
  231. char *PWM_Sysfs_Bebop::_generate_period_path(uint8_t channel)
  232. {
  233. char *path;
  234. int r = asprintf(&path, "/sys/class/pwm/pwm_%u/period_ns",
  235. channel);
  236. if (r == -1) {
  237. AP_HAL::panic("LinuxPWM_Sysfs :"
  238. "couldn't allocate period path\n");
  239. }
  240. return path;
  241. }
  242. PWM_Sysfs_Bebop::PWM_Sysfs_Bebop(uint8_t channel) :
  243. PWM_Sysfs_Base(_generate_export_path(),
  244. nullptr,
  245. _generate_enable_path(channel),
  246. _generate_duty_path(channel),
  247. _generate_period_path(channel),
  248. channel)
  249. {
  250. }
  251. }