APM:Libraries
Public Types | Public Member Functions | Protected Member Functions | Private Attributes | List of all members
Linux::PWM_Sysfs_Base Class Reference

#include <PWM_Sysfs.h>

Inheritance diagram for Linux::PWM_Sysfs_Base:
[legend]

Public Types

enum  Polarity { NORMAL = 0, INVERSE = 1 }
 

Public Member Functions

virtual ~PWM_Sysfs_Base ()
 
void init ()
 
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 ()
 
bool set_duty_cycle (uint32_t nsec_duty_cycle)
 
uint32_t get_duty_cycle ()
 
virtual void set_polarity (PWM_Sysfs_Base::Polarity polarity)
 
virtual PWM_Sysfs_Base::Polarity get_polarity ()
 

Protected Member Functions

 PWM_Sysfs_Base (char *export_path, char *polarity_path, char *enable_path, char *duty_path, char *period_path, uint8_t channel)
 

Private Attributes

uint32_t _nsec_duty_cycle_value = 0
 
int _duty_cycle_fd = -1
 
uint8_t _channel
 
char * _export_path = nullptr
 
char * _polarity_path = nullptr
 
char * _enable_path = nullptr
 
char * _duty_path = nullptr
 
char * _period_path = nullptr
 

Detailed Description

Definition at line 10 of file PWM_Sysfs.h.

Member Enumeration Documentation

◆ Polarity

Enumerator
NORMAL 
INVERSE 

Definition at line 14 of file PWM_Sysfs.h.

Constructor & Destructor Documentation

◆ ~PWM_Sysfs_Base()

Linux::PWM_Sysfs_Base::~PWM_Sysfs_Base ( )
virtual

Definition at line 45 of file PWM_Sysfs.cpp.

Here is the call graph for this function:

◆ PWM_Sysfs_Base()

Linux::PWM_Sysfs_Base::PWM_Sysfs_Base ( char *  export_path,
char *  polarity_path,
char *  enable_path,
char *  duty_path,
char *  period_path,
uint8_t  channel 
)
protected

Definition at line 33 of file PWM_Sysfs.cpp.

Member Function Documentation

◆ enable()

void Linux::PWM_Sysfs_Base::enable ( bool  value)

Definition at line 76 of file PWM_Sysfs.cpp.

Referenced by Linux::RCOutput_Sysfs::disable_ch(), Linux::RCOutput_Sysfs::enable_ch(), Linux::HeatPwm::HeatPwm(), DiscoLED::hw_init(), Linux::RCOutput_Sysfs::init(), and Linux::OpticalFlow_Onboard::init().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_duty_cycle()

uint32_t Linux::PWM_Sysfs_Base::get_duty_cycle ( )

Definition at line 138 of file PWM_Sysfs.cpp.

◆ get_freq()

uint32_t Linux::PWM_Sysfs_Base::get_freq ( )

Definition at line 122 of file PWM_Sysfs.cpp.

Referenced by Linux::RCOutput_Sysfs::get_freq().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_period()

uint32_t Linux::PWM_Sysfs_Base::get_period ( )

Definition at line 105 of file PWM_Sysfs.cpp.

Referenced by get_freq(), and DiscoLED::hw_init().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_polarity()

PWM_Sysfs_Base::Polarity Linux::PWM_Sysfs_Base::get_polarity ( )
virtual

Reimplemented in Linux::PWM_Sysfs_Bebop.

Definition at line 153 of file PWM_Sysfs.cpp.

Here is the call graph for this function:

◆ init()

void Linux::PWM_Sysfs_Base::init ( void  )

Definition at line 54 of file PWM_Sysfs.cpp.

Referenced by Linux::HeatPwm::HeatPwm(), DiscoLED::hw_init(), Linux::RCOutput_Sysfs::init(), and Linux::OpticalFlow_Onboard::init().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ is_enabled()

bool Linux::PWM_Sysfs_Base::is_enabled ( )

Definition at line 84 of file PWM_Sysfs.cpp.

Here is the call graph for this function:

◆ set_duty_cycle()

bool Linux::PWM_Sysfs_Base::set_duty_cycle ( uint32_t  nsec_duty_cycle)

Definition at line 127 of file PWM_Sysfs.cpp.

Referenced by Linux::HeatPwm::HeatPwm(), DiscoLED::hw_set_rgb(), Linux::RCOutput_Sysfs::init(), Linux::RCOutput_Sysfs::push(), Linux::HeatPwm::set_imu_temp(), set_period(), and Linux::RCOutput_Sysfs::write().

Here is the caller graph for this function:

◆ set_freq()

void Linux::PWM_Sysfs_Base::set_freq ( uint32_t  freq)

Definition at line 117 of file PWM_Sysfs.cpp.

Referenced by Linux::RCOutput_Sysfs::init(), Linux::OpticalFlow_Onboard::init(), and Linux::RCOutput_Sysfs::set_freq().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_period()

void Linux::PWM_Sysfs_Base::set_period ( uint32_t  nsec_period)

Definition at line 95 of file PWM_Sysfs.cpp.

Referenced by Linux::HeatPwm::HeatPwm(), and set_freq().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ set_polarity()

void Linux::PWM_Sysfs_Base::set_polarity ( PWM_Sysfs_Base::Polarity  polarity)
virtual

Reimplemented in Linux::PWM_Sysfs_Bebop.

Definition at line 143 of file PWM_Sysfs.cpp.

Referenced by Linux::RCOutput_Sysfs::init().

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ _channel

uint8_t Linux::PWM_Sysfs_Base::_channel
private

Definition at line 50 of file PWM_Sysfs.h.

Referenced by init().

◆ _duty_cycle_fd

int Linux::PWM_Sysfs_Base::_duty_cycle_fd = -1
private

Definition at line 49 of file PWM_Sysfs.h.

Referenced by init(), set_duty_cycle(), and ~PWM_Sysfs_Base().

◆ _duty_path

char* Linux::PWM_Sysfs_Base::_duty_path = nullptr
private

Definition at line 54 of file PWM_Sysfs.h.

Referenced by init().

◆ _enable_path

char* Linux::PWM_Sysfs_Base::_enable_path = nullptr
private

Definition at line 53 of file PWM_Sysfs.h.

Referenced by enable(), init(), is_enabled(), and ~PWM_Sysfs_Base().

◆ _export_path

char* Linux::PWM_Sysfs_Base::_export_path = nullptr
private

Definition at line 51 of file PWM_Sysfs.h.

Referenced by init().

◆ _nsec_duty_cycle_value

uint32_t Linux::PWM_Sysfs_Base::_nsec_duty_cycle_value = 0
private

Definition at line 48 of file PWM_Sysfs.h.

Referenced by get_duty_cycle(), and set_duty_cycle().

◆ _period_path

char* Linux::PWM_Sysfs_Base::_period_path = nullptr
private

Definition at line 55 of file PWM_Sysfs.h.

Referenced by get_period(), init(), set_period(), and ~PWM_Sysfs_Base().

◆ _polarity_path

char* Linux::PWM_Sysfs_Base::_polarity_path = nullptr
private

Definition at line 52 of file PWM_Sysfs.h.

Referenced by get_polarity(), set_polarity(), and ~PWM_Sysfs_Base().


The documentation for this class was generated from the following files: