22 #define PCA9685_ADDRESS 0x40 23 #define PCA9685_PWM 0x6 57 uint16_t red_adjusted =
rgb.r * 0x10;
58 uint16_t green_adjusted =
rgb.g * 0x10;
59 uint16_t blue_adjusted =
rgb.b * 0x10;
61 uint8_t blue_channel_lsb = blue_adjusted & 0xFF;
62 uint8_t blue_channel_msb = blue_adjusted >> 8;
64 uint8_t green_channel_lsb = green_adjusted & 0xFF;
65 uint8_t green_channel_msb = green_adjusted >> 8;
67 uint8_t red_channel_lsb = red_adjusted & 0xFF;
68 uint8_t red_channel_msb = red_adjusted >> 8;
71 uint8_t transaction[] = {
PCA9685_PWM, 0x00, 0x00, blue_channel_lsb, blue_channel_msb,
72 0x00, 0x00, green_channel_lsb, green_channel_msb,
73 0x00, 0x00, red_channel_lsb, red_channel_msb};
75 _dev->
transfer(transaction,
sizeof(transaction),
nullptr, 0);
virtual Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, Device::PeriodicCb) override=0
struct NavioLED_I2C::@156 rgb
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
bool hw_init(void) override
bool hw_set_rgb(uint8_t r, uint8_t g, uint8_t b) override
AP_HAL::OwnPtr< AP_HAL::I2CDevice > _dev
virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override=0
AP_HAL::I2CDeviceManager * i2c_mgr
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
virtual OwnPtr< AP_HAL::I2CDevice > get_device(uint8_t bus, uint8_t address, uint32_t bus_clock=400000, bool use_smbus=false, uint32_t timeout_ms=4)=0