2015-10-01 18:19:15 -03:00
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
|
|
|
|
#include "AP_HAL_Linux.h"
|
|
|
|
#include "Util.h"
|
|
|
|
|
2016-07-29 16:14:02 -03:00
|
|
|
namespace Linux {
|
|
|
|
|
|
|
|
class PWM_Sysfs_Base {
|
2015-10-01 18:19:15 -03:00
|
|
|
public:
|
2015-12-01 14:25:12 -04:00
|
|
|
virtual ~PWM_Sysfs_Base();
|
2015-10-01 18:19:15 -03:00
|
|
|
|
|
|
|
enum Polarity {
|
|
|
|
NORMAL = 0,
|
|
|
|
INVERSE = 1,
|
|
|
|
};
|
|
|
|
|
2016-10-27 04:46:08 -03:00
|
|
|
void init();
|
2015-11-05 23:17:32 -04:00
|
|
|
void enable(bool value);
|
2015-10-01 18:19:15 -03:00
|
|
|
bool is_enabled();
|
|
|
|
void set_period(uint32_t nsec_period);
|
|
|
|
uint32_t get_period();
|
|
|
|
void set_freq(uint32_t freq);
|
|
|
|
uint32_t get_freq();
|
2015-11-05 23:17:32 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
* 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.
|
|
|
|
*/
|
2015-10-01 18:19:15 -03:00
|
|
|
uint32_t get_duty_cycle();
|
2015-11-05 23:17:32 -04:00
|
|
|
|
2015-11-30 08:54:34 -04:00
|
|
|
virtual void set_polarity(PWM_Sysfs_Base::Polarity polarity);
|
|
|
|
virtual PWM_Sysfs_Base::Polarity get_polarity();
|
2015-11-26 09:19:11 -04:00
|
|
|
|
|
|
|
protected:
|
|
|
|
PWM_Sysfs_Base(char *export_path, char *polarity_path,
|
|
|
|
char *enable_path, char *duty_path,
|
|
|
|
char *period_path, uint8_t channel);
|
|
|
|
private:
|
|
|
|
uint32_t _nsec_duty_cycle_value = 0;
|
|
|
|
int _duty_cycle_fd = -1;
|
2016-10-27 04:46:08 -03:00
|
|
|
uint8_t _channel;
|
2016-10-30 02:24:21 -03:00
|
|
|
char *_export_path = nullptr;
|
|
|
|
char *_polarity_path = nullptr;
|
|
|
|
char *_enable_path = nullptr;
|
|
|
|
char *_duty_path = nullptr;
|
|
|
|
char *_period_path = nullptr;
|
2015-11-26 09:19:11 -04:00
|
|
|
};
|
|
|
|
|
2016-07-29 16:14:02 -03:00
|
|
|
class PWM_Sysfs : public PWM_Sysfs_Base {
|
2015-11-26 09:19:11 -04:00
|
|
|
public:
|
|
|
|
PWM_Sysfs(uint8_t chip, uint8_t channel);
|
2015-10-01 18:19:15 -03:00
|
|
|
|
|
|
|
private:
|
2015-11-26 09:19:11 -04:00
|
|
|
char *_generate_export_path(uint8_t chip);
|
|
|
|
char *_generate_polarity_path(uint8_t chip, uint8_t channel);
|
|
|
|
char *_generate_enable_path(uint8_t chip, uint8_t channel);
|
|
|
|
char *_generate_duty_path(uint8_t chip, uint8_t channel);
|
|
|
|
char *_generate_period_path(uint8_t chip, uint8_t channel);
|
|
|
|
};
|
|
|
|
|
2016-07-29 16:14:02 -03:00
|
|
|
class PWM_Sysfs_Bebop : public PWM_Sysfs_Base {
|
2015-11-26 09:19:11 -04:00
|
|
|
public:
|
|
|
|
PWM_Sysfs_Bebop(uint8_t channel);
|
|
|
|
|
|
|
|
private:
|
|
|
|
char *_generate_export_path();
|
|
|
|
char *_generate_polarity_path(uint8_t channel);
|
|
|
|
char *_generate_enable_path(uint8_t channel);
|
|
|
|
char *_generate_duty_path(uint8_t channel);
|
|
|
|
char *_generate_period_path(uint8_t channel);
|
|
|
|
|
2015-11-30 08:54:34 -04:00
|
|
|
void set_polarity(PWM_Sysfs_Base::Polarity polarity) override { }
|
|
|
|
|
|
|
|
PWM_Sysfs_Base::Polarity get_polarity() override
|
|
|
|
{
|
|
|
|
return PWM_Sysfs::NORMAL;
|
|
|
|
}
|
2015-10-01 18:19:15 -03:00
|
|
|
};
|
2016-07-29 16:14:02 -03:00
|
|
|
|
|
|
|
}
|