41 #include <sys/ioctl.h> 43 #include <linux/i2c-dev.h> 54 #include <px4_platform_common/log.h> 73 if (num_outputs > 16) {
77 for (
int i = 0; i < num_outputs; ++i) {
119 uint8_t newmode = (oldmode & 0x7F) | 0x10;
154 if (
write(fd, buf, 1) != 1) {
158 if (
read(fd, buf, 1) != 1) {
171 if (
write(fd, buf,
sizeof(buf)) !=
sizeof(buf)) {
172 PX4_ERR(
"Write failed (%i)", errno);
180 snprintf(bus_file,
sizeof(bus_file),
"/dev/i2c-%d", bus);
182 if ((fd = open(bus_file, O_RDWR)) < 0) {
183 PX4_ERR(
"Couldn't open I2C Bus %d [open_fd():open %d]", bus, errno);
187 if (ioctl(fd, I2C_SLAVE, address) < 0) {
188 PX4_ERR(
"I2C slave %d failed [open_fd():ioctl %d]", address, errno);
void reset()
Sets PCA9685 mode to 00.
#define PCA9685_DEFAULT_I2C_BUS
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.
static void read(bootloader_app_shared_t *pshared)
static void write(bootloader_app_shared_t *pshared)
#define PCA9685_DEFAULT_I2C_ADDR
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.