mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_Linux: rework PWM_Sysfs
This include some minor changes on all methods of PWM_Sysfs: - Sort headers - Add code inside Linux namespace rather than just use the namespace - Declare a union pwm_params, that's only used to calculate at compile time the maximum stack space we need in our methods: this is a bit safer for future extensions - Standardize error messages to include the useful params first and then the error message - Remove log message from hot path - Don't abuse macros for checking error - convert the SNPRINTF_CHECK macro into proper code, ignoring errors for not enough space since they can't happen - Fix call to read_file() passing uint8_t for "%u" in get_period() - Fix passing char** instead of char* to write_file() in set_polarity() - Use strncmp() instead of strncasecmp() since the kernel API uses lowercase. - Add comments on the 2 main methods of this class
This commit is contained in:
parent
39bd5fa80e
commit
c66c61180a
|
@ -22,27 +22,29 @@
|
|||
|
||||
#include "PWM_Sysfs.h"
|
||||
|
||||
#include <AP_Math/AP_Math.h>
|
||||
|
||||
#include <fcntl.h>
|
||||
#include <errno.h>
|
||||
#include <fcntl.h>
|
||||
#include <inttypes.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <unistd.h>
|
||||
|
||||
using namespace Linux;
|
||||
#include <AP_Math/AP_Math.h>
|
||||
|
||||
static const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
static const AP_HAL::HAL &hal = AP_HAL::get_HAL();
|
||||
|
||||
#define BASE_PWM_PATH "/sys/class/pwm/pwmchip"
|
||||
namespace Linux {
|
||||
|
||||
/*
|
||||
* IMPORTANT: The maximum path that is needed to setup a PWM channel, when using it make
|
||||
* sure that this size is enough for your use.
|
||||
*/
|
||||
#define PWM_PATH_MAX sizeof(BASE_PWM_PATH "XXX/pwmXXX/duty_cycle")
|
||||
|
||||
#define SNPRINTF_CHECK ret < 0 || ret >= (int)PWM_PATH_MAX
|
||||
/* Trick to use minimum stack space for each of the params */
|
||||
union pwm_params {
|
||||
char export_gpio[sizeof("XXX/export")];
|
||||
char duty_cycle[sizeof("XXX/pwmXXX/duty_cycle")];
|
||||
char enable[sizeof("XXX/pwmXXX/enable")];
|
||||
char period[sizeof("XXX/pwmXXX/period")];
|
||||
char polarity[sizeof("XXX/pwmXXX/polarity")];
|
||||
};
|
||||
#define PWM_BASE_PATH "/sys/class/pwm/pwmchip"
|
||||
#define PWM_PATH_MAX (sizeof(PWM_BASE_PATH) + sizeof(pwm_params) - 1)
|
||||
|
||||
PWM_Sysfs::PWM_Sysfs(uint8_t chip, uint8_t channel)
|
||||
: _chip(chip)
|
||||
|
@ -51,12 +53,15 @@ PWM_Sysfs::PWM_Sysfs(uint8_t chip, uint8_t channel)
|
|||
, _nsec_duty_cycle_value(0)
|
||||
{
|
||||
char path[PWM_PATH_MAX];
|
||||
int r;
|
||||
|
||||
int ret = snprintf(path, sizeof(path), BASE_PWM_PATH "%d/export", _chip);
|
||||
if (SNPRINTF_CHECK) {
|
||||
hal.scheduler->panic("LinuxPWM_Sysfs: Error formating channel export "
|
||||
"path of chip=%d channel=%d", _chip, _channel);
|
||||
r = snprintf(path, sizeof(path), PWM_BASE_PATH "%u/export", _chip);
|
||||
if (r < 0 || r >= (int)sizeof(path)) {
|
||||
hal.scheduler->panic("LinuxPWM_Sysfs: chip=%u channel=%u "
|
||||
"Error formatting pwm export: %s",
|
||||
_chip, _channel, strerror(errno));
|
||||
}
|
||||
|
||||
/*
|
||||
* Not checking for write errors here because if the PWM channel was
|
||||
* already exported, the write will return a EBUSY and we can catch up
|
||||
|
@ -64,15 +69,19 @@ PWM_Sysfs::PWM_Sysfs(uint8_t chip, uint8_t channel)
|
|||
*/
|
||||
Util::from(hal.util)->write_file(path, "%u", _channel);
|
||||
|
||||
ret = snprintf(path, sizeof(path), BASE_PWM_PATH "%d/pwm%d/duty_cycle", _chip, _channel);
|
||||
if (SNPRINTF_CHECK) {
|
||||
hal.scheduler->panic("LinuxPWM_Sysfs: Error formating channel duty cycle "
|
||||
"path of chip=%d channel=%d", _chip, _channel);
|
||||
r = snprintf(path, sizeof(path), PWM_BASE_PATH "%u/pwm%u/duty_cycle",
|
||||
_chip, _channel);
|
||||
if (r < 0 || r >= (int)sizeof(path)) {
|
||||
hal.scheduler->panic("LinuxPWM_Sysfs: chip=%u channel=%u "
|
||||
"Error formatting channel duty cycle: %s",
|
||||
_chip, _channel, strerror(errno));
|
||||
}
|
||||
|
||||
_duty_cycle_fd = ::open(path, O_RDWR | O_CLOEXEC);
|
||||
if (_duty_cycle_fd < 0) {
|
||||
hal.scheduler->panic("LinuxPWM_Sysfs: Unable to open file descriptor of chip=%d channel=%d",
|
||||
_chip, _channel);
|
||||
hal.scheduler->panic("LinuxPWM_Sysfs: chip=%u channel=%u "
|
||||
"Unable to open file %s: %s",
|
||||
_chip, _channel, path, strerror(errno));
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -83,25 +92,32 @@ PWM_Sysfs::~PWM_Sysfs()
|
|||
}
|
||||
}
|
||||
|
||||
void PWM_Sysfs::enable(bool enable)
|
||||
void PWM_Sysfs::enable(bool value)
|
||||
{
|
||||
char path[PWM_PATH_MAX];
|
||||
|
||||
int ret = snprintf(path, sizeof(path), BASE_PWM_PATH "%d/pwm%d/enable", _chip, _channel);
|
||||
if (SNPRINTF_CHECK || Util::from(hal.util)->write_file(path, "%u", enable) < 0) {
|
||||
hal.console->printf("LinuxPWM_Sysfs: Unable to %s chip=%d channel=%d\n",
|
||||
enable ? "enable" : "disable", _chip, _channel);
|
||||
int r = snprintf(path, sizeof(path), PWM_BASE_PATH "%u/pwm%u/enable",
|
||||
_chip, _channel);
|
||||
if (r < 0 || r >= (int)sizeof(path)
|
||||
|| Util::from(hal.util)->write_file(path, "%u", value) < 0) {
|
||||
hal.console->printf("LinuxPWM_Sysfs: chip=%u channel=%u "
|
||||
"Unable to %s\n",
|
||||
_chip, _channel,
|
||||
value ? "enable" : "disable");
|
||||
}
|
||||
}
|
||||
|
||||
bool PWM_Sysfs::is_enabled()
|
||||
{
|
||||
char path[PWM_PATH_MAX];
|
||||
uint8_t enabled;
|
||||
unsigned int enabled;
|
||||
|
||||
int ret = snprintf(path, sizeof(path), BASE_PWM_PATH "%d/pwm%d/enable", _chip, _channel);
|
||||
if (SNPRINTF_CHECK || Util::from(hal.util)->read_file(path, "%u", &enabled) < 0) {
|
||||
hal.console->printf("LinuxPWM_Sysfs: Unable to get status of chip=%d channel=%d\n",
|
||||
int r = snprintf(path, sizeof(path), PWM_BASE_PATH "%u/pwm%u/enable",
|
||||
_chip, _channel);
|
||||
if (r < 0 || r >= (int)sizeof(path)
|
||||
|| Util::from(hal.util)->read_file(path, "%u", &enabled) < 0) {
|
||||
hal.console->printf("LinuxPWM_Sysfs: chip=%u channel=%u "
|
||||
"Unable to get status\n",
|
||||
_chip, _channel);
|
||||
}
|
||||
|
||||
|
@ -112,9 +128,12 @@ void PWM_Sysfs::set_period(uint32_t nsec_period)
|
|||
{
|
||||
char path[PWM_PATH_MAX];
|
||||
|
||||
int ret = snprintf(path, sizeof(path), BASE_PWM_PATH "%d/pwm%d/period", _chip, _channel);
|
||||
if (SNPRINTF_CHECK || Util::from(hal.util)->write_file(path, "%u", nsec_period) < 0) {
|
||||
hal.console->printf("LinuxPWM_Sysfs: Unable to set period of chip=%d channel=%d\n",
|
||||
int r = snprintf(path, sizeof(path), PWM_BASE_PATH "%u/pwm%u/period",
|
||||
_chip, _channel);
|
||||
if (r < 0 || r >= (int)sizeof(path)
|
||||
|| Util::from(hal.util)->write_file(path, "%u", nsec_period) < 0) {
|
||||
hal.console->printf("LinuxPWM_Sysfs: chip=%u channel=%u "
|
||||
"Unable to set period\n",
|
||||
_chip, _channel);
|
||||
}
|
||||
}
|
||||
|
@ -124,9 +143,12 @@ uint32_t PWM_Sysfs::get_period()
|
|||
char path[PWM_PATH_MAX];
|
||||
uint32_t nsec_period;
|
||||
|
||||
int ret = snprintf(path, sizeof(path), BASE_PWM_PATH "%d/pwm%d/period", _chip, _channel);
|
||||
if (SNPRINTF_CHECK || Util::from(hal.util)->read_file(path, "%u", &nsec_period) < 0) {
|
||||
hal.console->printf("LinuxPWM_Sysfs: Unable to get period of chip=%d channel=%d\n",
|
||||
int r = snprintf(path, sizeof(path), PWM_BASE_PATH "%u/pwm%u/period",
|
||||
_chip, _channel);
|
||||
if (r < 0 || r >= (int)sizeof(path)
|
||||
|| Util::from(hal.util)->read_file(path, "%u", &nsec_period) < 0) {
|
||||
hal.console->printf("LinuxPWM_Sysfs: chip=%u channel=%u "
|
||||
"Unable to get period\n",
|
||||
_chip, _channel);
|
||||
return 0;
|
||||
}
|
||||
|
@ -144,14 +166,15 @@ uint32_t PWM_Sysfs::get_freq()
|
|||
return nsec_to_hz(get_period());
|
||||
}
|
||||
|
||||
void PWM_Sysfs::set_duty_cycle(uint32_t nsec_duty_cycle)
|
||||
bool PWM_Sysfs::set_duty_cycle(uint32_t nsec_duty_cycle)
|
||||
{
|
||||
/* Don't log fails since this could spam the console */
|
||||
if (dprintf(_duty_cycle_fd, "%u", nsec_duty_cycle) < 0) {
|
||||
hal.console->printf("LinuxPWM_Sysfs: Unable to set duty cycle of chip=%d channel=%d\n",
|
||||
_chip, _channel);
|
||||
} else {
|
||||
_nsec_duty_cycle_value = nsec_duty_cycle;
|
||||
return false;
|
||||
}
|
||||
|
||||
_nsec_duty_cycle_value = nsec_duty_cycle;
|
||||
return true;
|
||||
}
|
||||
|
||||
uint32_t PWM_Sysfs::get_duty_cycle()
|
||||
|
@ -163,9 +186,13 @@ void PWM_Sysfs::set_polarity(PWM_Sysfs::Polarity polarity)
|
|||
{
|
||||
char path[PWM_PATH_MAX];
|
||||
|
||||
int ret = snprintf(path, sizeof(path), BASE_PWM_PATH "%d/pwm%d/polarity", _chip, _channel);
|
||||
if (SNPRINTF_CHECK || Util::from(hal.util)->write_file(path, "%s", polarity == NORMAL ? "normal" : "inversed") < 0) {
|
||||
hal.console->printf("LinuxPWM_Sysfs: Unable to set polarity of chip=%d channel=%d\n",
|
||||
int r = snprintf(path, sizeof(path), PWM_BASE_PATH "%u/pwm%u/polarity",
|
||||
_chip, _channel);
|
||||
|
||||
if (r < 0 || r >= (int)sizeof(path)
|
||||
|| Util::from(hal.util)->write_file(path, "%s", polarity == NORMAL ? "normal" : "inversed") < 0) {
|
||||
hal.console->printf("LinuxPWM_Sysfs: chip=%u channel=%u "
|
||||
"Unable to set polarity\n",
|
||||
_chip, _channel);
|
||||
}
|
||||
}
|
||||
|
@ -175,13 +202,17 @@ PWM_Sysfs::Polarity PWM_Sysfs::get_polarity()
|
|||
char path[PWM_PATH_MAX];
|
||||
char polarity[16];
|
||||
|
||||
int ret = snprintf(path, sizeof(path), BASE_PWM_PATH "%d/pwm%d/polarity", _chip, _channel);
|
||||
if (SNPRINTF_CHECK || Util::from(hal.util)->read_file(path, "%s", &polarity) < 0) {
|
||||
hal.console->printf("LinuxPWM_Sysfs: Unable to get polarity of chip=%d channel=%d\n",
|
||||
int r = snprintf(path, sizeof(path), PWM_BASE_PATH "%u/pwm%u/polarity",
|
||||
_chip, _channel);
|
||||
if (r < 0 || r >= (int)sizeof(path)
|
||||
|| Util::from(hal.util)->read_file(path, "%s", polarity) < 0) {
|
||||
hal.console->printf("LinuxPWM_Sysfs: chip=%u channel=%u "
|
||||
"Unable to get polarity\n",
|
||||
_chip, _channel);
|
||||
return NORMAL;
|
||||
}
|
||||
return strncasecmp("normal", polarity, sizeof("normal")) ? INVERSE : NORMAL;
|
||||
return strncmp(polarity, "normal", sizeof(polarity)) ? INVERSE : NORMAL;
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -15,14 +15,26 @@ public:
|
|||
INVERSE = 1,
|
||||
};
|
||||
|
||||
void enable(bool enable);
|
||||
void enable(bool value);
|
||||
bool is_enabled();
|
||||
void set_period(uint32_t nsec_period);
|
||||
uint32_t get_period();
|
||||
void set_freq(uint32_t freq);
|
||||
uint32_t get_freq();
|
||||
void set_duty_cycle(uint32_t nsec_duty_cycle);
|
||||
|
||||
/*
|
||||
* This is the main method, to be called on hot path. It doesn't log any
|
||||
* failure so not to risk flooding the log. If logging is necessary, check
|
||||
* the return value.
|
||||
*/
|
||||
bool set_duty_cycle(uint32_t nsec_duty_cycle);
|
||||
|
||||
/*
|
||||
* This is supposed to be called in the hot path, so it returns the cached
|
||||
* value rather than getting it from hardware.
|
||||
*/
|
||||
uint32_t get_duty_cycle();
|
||||
|
||||
void set_polarity(PWM_Sysfs::Polarity polarity);
|
||||
PWM_Sysfs::Polarity get_polarity();
|
||||
|
||||
|
@ -32,5 +44,3 @@ private:
|
|||
const uint16_t _channel;
|
||||
const uint8_t _chip;
|
||||
};
|
||||
|
||||
|
||||
|
|
Loading…
Reference in New Issue