49 #define MODE1 0x00 //Mode register 1 50 #define MODE2 0x01 //Mode register 2 51 #define SUBADR1 0x02 //I2C-bus subaddress 1 52 #define SUBADR2 0x03 //I2C-bus subaddress 2 53 #define SUBADR3 0x04 //I2C-bus subaddress 3 54 #define ALLCALLADR 0x05 //LED All Call I2C-bus address 55 #define LED0 0x6 //LED0 start register 56 #define LED0_ON_L 0x6 //LED0 output and brightness control byte 0 57 #define LED0_ON_H 0x7 //LED0 output and brightness control byte 1 58 #define LED0_OFF_L 0x8 //LED0 output and brightness control byte 2 59 #define LED0_OFF_H 0x9 //LED0 output and brightness control byte 3 60 #define LED_MULTIPLYER 4 // For the other 15 channels 61 #define ALLLED_ON_L 0xFA //load all the LEDn_ON registers, byte 0 (turn 0-7 channels on) 62 #define ALLLED_ON_H 0xFB //load all the LEDn_ON registers, byte 1 (turn 8-15 channels on) 63 #define ALLLED_OFF_L 0xFC //load all the LEDn_OFF registers, byte 0 (turn 0-7 channels off) 64 #define ALLLED_OFF_H 0xFD //load all the LEDn_OFF registers, byte 1 (turn 8-15 channels off) 65 #define PRE_SCALE 0xFE //prescaler for output frequency 66 #define MAX_PWM_RES 4096 //Resolution 4096=12bit 分辨率,按2的阶乘计算,12bit为4096 67 #define CLOCK_FREQ 25000000.0 //25MHz default osc clock 68 #define PCA9685_DEFAULT_I2C_ADDR 0x40 // default i2c address for pca9685 默认i2c地址为0x40 69 #define PCA9685_DEFAULT_I2C_BUS 1 // default i2c bus for pca9685 默认为1 85 int init()
override {
return _fd >= 0 ? 0 : -1; }
90 int init(
int bus,
int address);
109 void setPWM(uint8_t channel,
int on_value,
int off_value);
115 void setPWM(uint8_t channel,
int value);
140 int open_fd(
int bus,
int address);
void reset()
Sets PCA9685 mode to 00.
Main class that exports features for PCA9685 chip.
uint8_t read_byte(int fd, uint8_t address)
Read a single byte from PCA9685.
void setPWMFreq(int freq)
Set the frequency of PWM.
void write_byte(int fd, uint8_t address, uint8_t data)
Write a single byte to PCA9685.
int _fd
I2C device file descriptor.
class PWMOutBase common abstract PWM output base class
int send_output_pwm(const uint16_t *pwm, int num_outputs) override
int open_fd(int bus, int address)
Open device file for PCA9685 I2C bus.
void setPWM(uint8_t channel, int on_value, int off_value)
PWM a single channel with custom on time.