PX4 Firmware
PX4 Autopilot Software http://px4.io
|
Main class that exports features for PCA9685 chip. More...
#include <PCA9685.h>
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... | |
PCA9685::PCA9685 | ( | ) |
Definition at line 84 of file PCA9685.cpp.
References init(), PCA9685_DEFAULT_I2C_ADDR, and PCA9685_DEFAULT_I2C_BUS.
PCA9685::PCA9685 | ( | int | bus, |
int | address | ||
) |
Constructor takes bus and address arguments.
bus | the bus to use in /dev/i2c-d. |
address | the device address on bus |
Definition at line 89 of file PCA9685.cpp.
References init().
|
virtual |
Definition at line 94 of file PCA9685.cpp.
Referenced by 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().
int PCA9685::init | ( | int | bus, |
int | address | ||
) |
Definition at line 58 of file PCA9685.cpp.
References _fd, open_fd(), reset(), and setPWMFreq().
|
private |
Open device file for PCA9685 I2C bus.
Definition at line 176 of file PCA9685.cpp.
References fd.
Referenced by init().
|
private |
Read a single byte from PCA9685.
fd | file descriptor for I/O |
address | register address to read from |
Definition at line 148 of file PCA9685.cpp.
References read(), and write().
Referenced by setPWMFreq().
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().
|
overridevirtual |
Implements linux_pwm_out::PWMOutBase.
Definition at line 71 of file PCA9685.cpp.
References setPWM().
Referenced by init().
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)
channel | |
on_value | 0-4095 value to turn on the pulse |
off_value | 0-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().
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().
void PCA9685::setPWMFreq | ( | int | freq | ) |
Set the frequency of PWM.
freq | desired 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().
|
private |
Write a single byte to PCA9685.
fd | file descriptor for I/O |
address | register address to write to |
data | 8 bit data to write |
Definition at line 165 of file PCA9685.cpp.
Referenced by reset(), setPWM(), and setPWMFreq().
|
private |
I2C device file descriptor.
Definition at line 118 of file PCA9685.h.
Referenced by init(), reset(), setPWM(), setPWMFreq(), and ~PCA9685().