PWM_Sysfs.h 2.3 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889
  1. #pragma once
  2. #include <AP_HAL/AP_HAL.h>
  3. #include "AP_HAL_Linux.h"
  4. #include "Util.h"
  5. namespace Linux {
  6. class PWM_Sysfs_Base {
  7. public:
  8. virtual ~PWM_Sysfs_Base();
  9. enum Polarity {
  10. NORMAL = 0,
  11. INVERSE = 1,
  12. };
  13. void init();
  14. void enable(bool value);
  15. bool is_enabled();
  16. void set_period(uint32_t nsec_period);
  17. uint32_t get_period();
  18. void set_freq(uint32_t freq);
  19. uint32_t get_freq();
  20. /*
  21. * This is the main method, to be called on hot path. It doesn't log any
  22. * failure so not to risk flooding the log. If logging is necessary, check
  23. * the return value.
  24. */
  25. bool set_duty_cycle(uint32_t nsec_duty_cycle);
  26. /*
  27. * This is supposed to be called in the hot path, so it returns the cached
  28. * value rather than getting it from hardware.
  29. */
  30. uint32_t get_duty_cycle();
  31. virtual void set_polarity(PWM_Sysfs_Base::Polarity polarity);
  32. virtual PWM_Sysfs_Base::Polarity get_polarity();
  33. protected:
  34. PWM_Sysfs_Base(char *export_path, char *polarity_path,
  35. char *enable_path, char *duty_path,
  36. char *period_path, uint8_t channel);
  37. private:
  38. uint32_t _nsec_duty_cycle_value = 0;
  39. int _duty_cycle_fd = -1;
  40. uint8_t _channel;
  41. char *_export_path = nullptr;
  42. char *_polarity_path = nullptr;
  43. char *_enable_path = nullptr;
  44. char *_duty_path = nullptr;
  45. char *_period_path = nullptr;
  46. };
  47. class PWM_Sysfs : public PWM_Sysfs_Base {
  48. public:
  49. PWM_Sysfs(uint8_t chip, uint8_t channel);
  50. private:
  51. char *_generate_export_path(uint8_t chip);
  52. char *_generate_polarity_path(uint8_t chip, uint8_t channel);
  53. char *_generate_enable_path(uint8_t chip, uint8_t channel);
  54. char *_generate_duty_path(uint8_t chip, uint8_t channel);
  55. char *_generate_period_path(uint8_t chip, uint8_t channel);
  56. };
  57. class PWM_Sysfs_Bebop : public PWM_Sysfs_Base {
  58. public:
  59. PWM_Sysfs_Bebop(uint8_t channel);
  60. private:
  61. char *_generate_export_path();
  62. char *_generate_polarity_path(uint8_t channel);
  63. char *_generate_enable_path(uint8_t channel);
  64. char *_generate_duty_path(uint8_t channel);
  65. char *_generate_period_path(uint8_t channel);
  66. void set_polarity(PWM_Sysfs_Base::Polarity polarity) override { }
  67. PWM_Sysfs_Base::Polarity get_polarity() override
  68. {
  69. return PWM_Sysfs::NORMAL;
  70. }
  71. };
  72. }