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