PX4 Firmware
PX4 Autopilot Software http://px4.io
linux_pwm_out::PCA9685 Class Reference

Main class that exports features for PCA9685 chip. More...

#include <PCA9685.h>

Inheritance diagram for linux_pwm_out::PCA9685:
Collaboration diagram for linux_pwm_out::PCA9685:

Public Member Functions

 PCA9685 ()
 
 PCA9685 (int bus, int address)
 Constructor takes bus and address arguments. More...
 
int init () override
 
int send_output_pwm (const uint16_t *pwm, int num_outputs) override
 
int init (int bus, int address)
 
virtual ~PCA9685 ()
 
void reset ()
 Sets PCA9685 mode to 00. More...
 
void setPWMFreq (int freq)
 Set the frequency of PWM. More...
 
void setPWM (uint8_t channel, int on_value, int off_value)
 PWM a single channel with custom on time. More...
 
void setPWM (uint8_t channel, int value)
 send pwm value to led(channel), value should be range of 0-4095 More...
 
- Public Member Functions inherited from linux_pwm_out::PWMOutBase
virtual ~PWMOutBase ()
 

Private Member Functions

uint8_t read_byte (int fd, uint8_t address)
 Read a single byte from PCA9685. More...
 
void write_byte (int fd, uint8_t address, uint8_t data)
 Write a single byte to PCA9685. More...
 
int open_fd (int bus, int address)
 Open device file for PCA9685 I2C bus. More...
 

Private Attributes

int _fd = -1
 I2C device file descriptor. More...
 

Detailed Description

Main class that exports features for PCA9685 chip.

Definition at line 72 of file PCA9685.h.

Constructor & Destructor Documentation

◆ PCA9685() [1/2]

PCA9685::PCA9685 ( )

Definition at line 84 of file PCA9685.cpp.

References init(), PCA9685_DEFAULT_I2C_ADDR, and PCA9685_DEFAULT_I2C_BUS.

Here is the call graph for this function:

◆ PCA9685() [2/2]

PCA9685::PCA9685 ( int  bus,
int  address 
)

Constructor takes bus and address arguments.

Parameters
busthe bus to use in /dev/i2c-d.
addressthe device address on bus

Definition at line 89 of file PCA9685.cpp.

References init().

Here is the call graph for this function:

◆ ~PCA9685()

PCA9685::~PCA9685 ( )
virtual

Definition at line 94 of file PCA9685.cpp.

References _fd, and reset().

Referenced by init().

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

Member Function Documentation

◆ init() [1/2]

int linux_pwm_out::PCA9685::init ( )
inlineoverridevirtual

Implements linux_pwm_out::PWMOutBase.

Definition at line 85 of file PCA9685.h.

References _fd, reset(), send_output_pwm(), setPWM(), setPWMFreq(), and ~PCA9685().

Referenced by PCA9685().

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

◆ init() [2/2]

int PCA9685::init ( int  bus,
int  address 
)

Definition at line 58 of file PCA9685.cpp.

References _fd, open_fd(), reset(), and setPWMFreq().

Here is the call graph for this function:

◆ open_fd()

int PCA9685::open_fd ( int  bus,
int  address 
)
private

Open device file for PCA9685 I2C bus.

Returns
fd returns the file descriptor number or -1 on error

Definition at line 176 of file PCA9685.cpp.

References fd.

Referenced by init().

Here is the caller graph for this function:

◆ read_byte()

uint8_t PCA9685::read_byte ( int  fd,
uint8_t  address 
)
private

Read a single byte from PCA9685.

Parameters
fdfile descriptor for I/O
addressregister address to read from
Returns
read byte

Definition at line 148 of file PCA9685.cpp.

References read(), and write().

Referenced by setPWMFreq().

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

◆ reset()

void PCA9685::reset ( )

Sets PCA9685 mode to 00.

Definition at line 103 of file PCA9685.cpp.

References _fd, MODE1, MODE2, and write_byte().

Referenced by init(), and ~PCA9685().

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

◆ send_output_pwm()

int PCA9685::send_output_pwm ( const uint16_t *  pwm,
int  num_outputs 
)
overridevirtual

Implements linux_pwm_out::PWMOutBase.

Definition at line 71 of file PCA9685.cpp.

References setPWM().

Referenced by init().

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

◆ setPWM() [1/2]

void PCA9685::setPWM ( uint8_t  channel,
int  on_value,
int  off_value 
)

PWM a single channel with custom on time.

send pwm vale to led(channel)

Parameters
channel
on_value0-4095 value to turn on the pulse
off_value0-4095 value to turn off the pulse

Definition at line 134 of file PCA9685.cpp.

References _fd, LED0_OFF_H, LED0_OFF_L, LED0_ON_H, LED0_ON_L, LED_MULTIPLYER, and write_byte().

Referenced by init(), send_output_pwm(), and setPWM().

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

◆ setPWM() [2/2]

void PCA9685::setPWM ( uint8_t  channel,
int  value 
)

send pwm value to led(channel), value should be range of 0-4095

Definition at line 129 of file PCA9685.cpp.

References setPWM().

Here is the call graph for this function:

◆ setPWMFreq()

void PCA9685::setPWMFreq ( int  freq)

Set the frequency of PWM.

Parameters
freqdesired frequency. 40Hz to 1000Hz using internal 25MHz oscillator.

Definition at line 111 of file PCA9685.cpp.

References _fd, CLOCK_FREQ, MAX_PWM_RES, MODE1, PRE_SCALE, read_byte(), and write_byte().

Referenced by init().

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

◆ write_byte()

void PCA9685::write_byte ( int  fd,
uint8_t  address,
uint8_t  data 
)
private

Write a single byte to PCA9685.

Parameters
fdfile descriptor for I/O
addressregister address to write to
data8 bit data to write

Definition at line 165 of file PCA9685.cpp.

References data, and write().

Referenced by reset(), setPWM(), and setPWMFreq().

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

Member Data Documentation

◆ _fd

int linux_pwm_out::PCA9685::_fd = -1
private

I2C device file descriptor.

Definition at line 118 of file PCA9685.h.

Referenced by init(), reset(), setPWM(), setPWMFreq(), and ~PCA9685().


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