APM:Libraries
PWM_Sysfs.cpp
Go to the documentation of this file.
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 
19 #include <errno.h>
20 #include <fcntl.h>
21 #include <inttypes.h>
22 #include <stdio.h>
23 #include <stdlib.h>
24 #include <unistd.h>
25 
26 #include <AP_HAL/AP_HAL.h>
27 #include <AP_Math/AP_Math.h>
28 
29 static const AP_HAL::HAL &hal = AP_HAL::get_HAL();
30 
31 namespace Linux {
32 
33 PWM_Sysfs_Base::PWM_Sysfs_Base(char* export_path, char* polarity_path,
34  char* enable_path, char* duty_path,
35  char* period_path, uint8_t channel)
36  : _export_path(export_path)
37  , _polarity_path(polarity_path)
38  , _enable_path(enable_path)
39  , _duty_path(duty_path)
40  , _period_path(period_path)
41  , _channel(channel)
42 {
43 }
44 
46 {
48 
52 }
53 
55 {
56  if (_export_path == nullptr || _enable_path == nullptr ||
57  _period_path == nullptr || _duty_path == nullptr) {
58  AP_HAL::panic("PWM_Sysfs: export=%p enable=%p period=%p duty=%p"
59  " required path is NULL", _export_path, _enable_path,
61  }
62  /* Not checking the return of write_file since it will fail if
63  * the pwm has already been exported
64  */
67 
68  _duty_cycle_fd = ::open(_duty_path, O_RDWR | O_CLOEXEC);
69  if (_duty_cycle_fd < 0) {
70  AP_HAL::panic("LinuxPWM_Sysfs:Unable to open file %s: %s",
72  }
74 }
75 
77 {
78  if (Util::from(hal.util)->write_file(_enable_path, "%u", value) < 0) {
79  hal.console->printf("LinuxPWM_Sysfs: %s Unable to %s\n",
80  _enable_path, value ? "enable" : "disable");
81  }
82 }
83 
85 {
86  unsigned int enabled;
87 
88  if (Util::from(hal.util)->read_file(_enable_path, "%u", &enabled) < 0) {
89  hal.console->printf("LinuxPWM_Sysfs: %s Unable to get status\n",
90  _enable_path);
91  }
92  return enabled;
93 }
94 
95 void PWM_Sysfs_Base::set_period(uint32_t nsec_period)
96 {
97  set_duty_cycle(0);
98 
99  if (Util::from(hal.util)->write_file(_period_path, "%u", nsec_period) < 0) {
100  hal.console->printf("LinuxPWM_Sysfs: %s Unable to set period\n",
101  _period_path);
102  }
103 }
104 
106 {
107  uint32_t nsec_period;
108 
109  if (Util::from(hal.util)->read_file(_period_path, "%u", &nsec_period) < 0) {
110  hal.console->printf("LinuxPWM_Sysfs: %s Unable to get period\n",
111  _period_path);
112  nsec_period = 0;
113  }
114  return nsec_period;
115 }
116 
117 void PWM_Sysfs_Base::set_freq(uint32_t freq)
118 {
119  set_period(hz_to_nsec(freq));
120 }
121 
123 {
124  return nsec_to_hz(get_period());
125 }
126 
127 bool PWM_Sysfs_Base::set_duty_cycle(uint32_t nsec_duty_cycle)
128 {
129  /* Don't log fails since this could spam the console */
130  if (dprintf(_duty_cycle_fd, "%u", nsec_duty_cycle) < 0) {
131  return false;
132  }
133 
134  _nsec_duty_cycle_value = nsec_duty_cycle;
135  return true;
136 }
137 
139 {
140  return _nsec_duty_cycle_value;
141 }
142 
144 {
145  if (Util::from(hal.util)->write_file(_polarity_path, "%s",
146  polarity == NORMAL ?
147  "normal" : "inversed") < 0) {
148  hal.console->printf("LinuxPWM_Sysfs: %s Unable to set polarity\n",
150  }
151 }
152 
154 {
155  char polarity[16];
156 
157  if (Util::from(hal.util)->read_file(_polarity_path, "%s", polarity) < 0) {
158  hal.console->printf("LinuxPWM_Sysfs: %s Unable to get polarity\n",
160  return NORMAL;
161  }
162  return strncmp(polarity, "normal", sizeof(polarity)) ? INVERSE : NORMAL;
163 }
164 
165 /* PWM Sysfs api for mainline kernel */
167 {
168  char *path;
169  int r = asprintf(&path, "/sys/class/pwm/pwmchip%u/export", chip);
170  if (r == -1) {
171  AP_HAL::panic("LinuxPWM_Sysfs :"
172  "couldn't allocate export path\n");
173  }
174  return path;
175 }
176 
177 char *PWM_Sysfs::_generate_polarity_path(uint8_t chip, uint8_t channel)
178 {
179  char *path;
180  int r = asprintf(&path, "/sys/class/pwm/pwmchip%u/pwm%u/polarity",
181  chip, channel);
182  if (r == -1) {
183  AP_HAL::panic("LinuxPWM_Sysfs :"
184  "couldn't allocate polarity path\n");
185  }
186  return path;
187 }
188 
189 char *PWM_Sysfs::_generate_enable_path(uint8_t chip, uint8_t channel)
190 {
191  char *path;
192  int r = asprintf(&path, "/sys/class/pwm/pwmchip%u/pwm%u/enable",
193  chip, channel);
194  if (r == -1) {
195  AP_HAL::panic("LinuxPWM_Sysfs :"
196  "couldn't allocate enable path\n");
197  }
198  return path;
199 }
200 
201 char *PWM_Sysfs::_generate_duty_path(uint8_t chip, uint8_t channel)
202 {
203  char *path;
204  int r = asprintf(&path, "/sys/class/pwm/pwmchip%u/pwm%u/duty_cycle",
205  chip, channel);
206  if (r == -1) {
207  AP_HAL::panic("LinuxPWM_Sysfs :"
208  "couldn't allocate duty path\n");
209  }
210  return path;
211 }
212 
213 char *PWM_Sysfs::_generate_period_path(uint8_t chip, uint8_t channel)
214 {
215  char *path;
216  int r = asprintf(&path, "/sys/class/pwm/pwmchip%u/pwm%u/period",
217  chip, channel);
218  if (r == -1) {
219  AP_HAL::panic("LinuxPWM_Sysfs :"
220  "couldn't allocate period path\n");
221  }
222  return path;
223 }
224 
225 PWM_Sysfs::PWM_Sysfs(uint8_t chip, uint8_t channel) :
226  PWM_Sysfs_Base(_generate_export_path(chip),
227  _generate_polarity_path(chip, channel),
228  _generate_enable_path(chip, channel),
229  _generate_duty_path(chip, channel),
230  _generate_period_path(chip, channel),
231  channel)
232 {
233 }
234 
235 /* PWM Sysfs api for bebop kernel */
237 {
238  return strdup("/sys/class/pwm/export");
239 }
240 
242 {
243  char *path;
244  int r = asprintf(&path, "/sys/class/pwm/pwm_%u/run",
245  channel);
246  if (r == -1) {
247  AP_HAL::panic("LinuxPWM_Sysfs :"
248  "couldn't allocate enable path\n");
249  }
250  return path;
251 }
252 
254 {
255  char *path;
256  int r = asprintf(&path, "/sys/class/pwm/pwm_%u/duty_ns",
257  channel);
258  if (r == -1) {
259  AP_HAL::panic("LinuxPWM_Sysfs :"
260  "couldn't allocate duty path\n");
261  }
262  return path;
263 }
264 
266 {
267  char *path;
268  int r = asprintf(&path, "/sys/class/pwm/pwm_%u/period_ns",
269  channel);
270  if (r == -1) {
271  AP_HAL::panic("LinuxPWM_Sysfs :"
272  "couldn't allocate period path\n");
273  }
274  return path;
275 }
276 
279  nullptr,
280  _generate_enable_path(channel),
281  _generate_duty_path(channel),
282  _generate_period_path(channel),
283  channel)
284 {
285 }
286 
287 }
char * _generate_duty_path(uint8_t channel)
Definition: PWM_Sysfs.cpp:253
char * _generate_polarity_path(uint8_t chip, uint8_t channel)
Definition: PWM_Sysfs.cpp:177
PWM_Sysfs(uint8_t chip, uint8_t channel)
Definition: PWM_Sysfs.cpp:225
uint32_t _nsec_duty_cycle_value
Definition: PWM_Sysfs.h:48
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
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
virtual ~PWM_Sysfs_Base()
Definition: PWM_Sysfs.cpp:45
AP_HAL::UARTDriver * console
Definition: HAL.h:110
char * _generate_period_path(uint8_t chip, uint8_t channel)
Definition: PWM_Sysfs.cpp:213
char * strerror(int errnum)
POSIX strerror() - convert POSIX errno to text with user message.
Definition: posix.c:1852
uint32_t hz_to_nsec(uint32_t freq)
Definition: AP_Math.h:207
AP_HAL::Util * util
Definition: HAL.h:115
int int read_file(const char *path, const char *fmt,...) FMT_SCANF(3
Definition: Util.cpp:151
static const AP_HAL::HAL & hal
Definition: PWM_Sysfs.cpp:29
char * _generate_export_path(uint8_t chip)
Definition: PWM_Sysfs.cpp:166
static Util * from(AP_HAL::Util *util)
Definition: Util.h:27
uint32_t nsec_to_hz(uint32_t nsec)
Definition: AP_Math.h:212
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
void set_period(uint32_t nsec_period)
Definition: PWM_Sysfs.cpp:95
int close(int fileno)
POSIX Close a file with fileno handel.
Definition: posix.c:675
char * _generate_duty_path(uint8_t chip, uint8_t channel)
Definition: PWM_Sysfs.cpp:201
const HAL & get_HAL()
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
void free(void *ptr)
Definition: malloc.c:81
char * _generate_enable_path(uint8_t channel)
Definition: PWM_Sysfs.cpp:241
char * _generate_period_path(uint8_t channel)
Definition: PWM_Sysfs.cpp:265
char * _generate_enable_path(uint8_t chip, uint8_t channel)
Definition: PWM_Sysfs.cpp:189
int write_file(const char *path, const char *fmt,...) FMT_PRINTF(3
Definition: Util.cpp:126
int errno
Note: fdevopen assigns stdin,stdout,stderr.
Definition: posix.c:118
float value
int asprintf(char **strp, const char *fmt,...)
Definition: stdio.c:91
void enable(bool value)
Definition: PWM_Sysfs.cpp:76
char * _generate_export_path()
Definition: PWM_Sysfs.cpp:236
PWM_Sysfs_Bebop(uint8_t channel)
Definition: PWM_Sysfs.cpp:277
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
void set_freq(uint32_t freq)
Definition: PWM_Sysfs.cpp:117