mirror of
https://github.com/ByteWelder/Tactility.git
synced 2026-06-19 04:15:06 +00:00
I2C updates
This commit is contained in:
parent
023b220bfb
commit
133215664c
@ -58,7 +58,7 @@ bool initBoot() {
|
||||
std::vector<tt::hal::gps::GpsConfiguration> gps_configurations;
|
||||
gps_service->getGpsConfigurations(gps_configurations);
|
||||
if (gps_configurations.empty()) {
|
||||
if (gps_service->addGpsConfiguration(tt::hal::gps::GpsConfiguration {.uartName = "uart1", .baudRate = 38400, .model = tt::hal::gps::GpsModel::UBLOX10})) {
|
||||
if (gps_service->addGpsConfiguration(tt::hal::gps::GpsConfiguration {.uartName = "uart0", .baudRate = 38400, .model = tt::hal::gps::GpsModel::UBLOX10})) {
|
||||
LOGGER.info("Configured internal GPS");
|
||||
} else {
|
||||
LOGGER.error("Failed to configure internal GPS");
|
||||
|
||||
@ -3,6 +3,7 @@
|
||||
#include <tactility/bindings/root.h>
|
||||
#include <tactility/bindings/esp32_ble.h>
|
||||
#include <tactility/bindings/esp32_gpio.h>
|
||||
#include <tactility/bindings/esp32_grove.h>
|
||||
#include <tactility/bindings/esp32_i2c.h>
|
||||
#include <tactility/bindings/esp32_i2s.h>
|
||||
#include <tactility/bindings/esp32_spi.h>
|
||||
@ -30,15 +31,6 @@
|
||||
pin-scl = <&gpio0 8 GPIO_FLAG_NONE>;
|
||||
};
|
||||
|
||||
i2c_external: i2c1 {
|
||||
compatible = "espressif,esp32-i2c";
|
||||
status = "disabled";
|
||||
port = <I2C_NUM_1>;
|
||||
clock-frequency = <400000>;
|
||||
pin-sda = <&gpio0 43 GPIO_FLAG_NONE>;
|
||||
pin-scl = <&gpio0 44 GPIO_FLAG_NONE>;
|
||||
};
|
||||
|
||||
i2s0 {
|
||||
compatible = "espressif,esp32-i2s";
|
||||
port = <I2S_NUM_0>;
|
||||
@ -55,7 +47,7 @@
|
||||
pin-sclk = <&gpio0 40 GPIO_FLAG_NONE>;
|
||||
};
|
||||
|
||||
uart1 {
|
||||
uart0 {
|
||||
compatible = "espressif,esp32-uart";
|
||||
port = <UART_NUM_1>;
|
||||
pin-tx = <&gpio0 43 GPIO_FLAG_NONE>;
|
||||
|
||||
@ -4,6 +4,7 @@
|
||||
#include "devices/TpagerKeyboard.h"
|
||||
#include "devices/TpagerPower.h"
|
||||
#include <driver/gpio.h>
|
||||
#include <tactility/device.h>
|
||||
|
||||
#include <Tactility/hal/Configuration.h>
|
||||
#include <Bq25896.h>
|
||||
@ -14,17 +15,18 @@ bool tpagerInit();
|
||||
using namespace tt::hal;
|
||||
|
||||
static DeviceVector createDevices() {
|
||||
auto bq27220 = std::make_shared<Bq27220>(I2C_NUM_0);
|
||||
auto* i2c = device_find_by_name("i2c0");
|
||||
auto bq27220 = std::make_shared<Bq27220>(i2c);
|
||||
auto power = std::make_shared<TpagerPower>(bq27220);
|
||||
|
||||
auto tca8418 = std::make_shared<Tca8418>(I2C_NUM_0);
|
||||
auto tca8418 = std::make_shared<Tca8418>(i2c);
|
||||
auto keyboard = std::make_shared<TpagerKeyboard>(tca8418);
|
||||
|
||||
return std::vector<std::shared_ptr<tt::hal::Device>> {
|
||||
tca8418,
|
||||
std::make_shared<Bq25896>(I2C_NUM_0),
|
||||
std::make_shared<Bq25896>(i2c),
|
||||
bq27220,
|
||||
std::make_shared<Drv2605>(I2C_NUM_0),
|
||||
std::make_shared<Drv2605>(i2c),
|
||||
power,
|
||||
createTpagerSdCard(),
|
||||
createDisplay(),
|
||||
|
||||
@ -4,6 +4,7 @@
|
||||
#include "devices/CardputerPower.h"
|
||||
#include <driver/gpio.h>
|
||||
|
||||
#include <tactility/device.h>
|
||||
#include <Tactility/hal/Configuration.h>
|
||||
|
||||
#include <PwmBacklight.h>
|
||||
@ -16,7 +17,7 @@ static bool initBoot() {
|
||||
}
|
||||
|
||||
static DeviceVector createDevices() {
|
||||
auto tca8418 = std::make_shared<Tca8418>(I2C_NUM_0);
|
||||
auto tca8418 = std::make_shared<Tca8418>(device_find_by_name("i2c_internal"));
|
||||
return {
|
||||
createSdCard(),
|
||||
createDisplay(),
|
||||
|
||||
@ -3,6 +3,7 @@
|
||||
#include <tactility/bindings/root.h>
|
||||
#include <tactility/bindings/esp32_ble.h>
|
||||
#include <tactility/bindings/esp32_gpio.h>
|
||||
#include <tactility/bindings/esp32_grove.h>
|
||||
#include <tactility/bindings/esp32_i2c.h>
|
||||
#include <tactility/bindings/esp32_i2s.h>
|
||||
#include <tactility/bindings/esp32_spi.h>
|
||||
@ -36,12 +37,14 @@
|
||||
};
|
||||
};
|
||||
|
||||
i2c_port_a {
|
||||
compatible = "espressif,esp32-i2c";
|
||||
port = <I2C_NUM_1>;
|
||||
clock-frequency = <400000>;
|
||||
pin-sda = <&gpio0 2 GPIO_FLAG_NONE>;
|
||||
pin-scl = <&gpio0 1 GPIO_FLAG_NONE>;
|
||||
port_a: grove0 {
|
||||
compatible = "espressif,esp32-grove";
|
||||
defaultMode = <GROVE_MODE_I2C>;
|
||||
pinSdaRx = <&gpio0 2 GPIO_FLAG_NONE>;
|
||||
pinSclTx = <&gpio0 1 GPIO_FLAG_NONE>;
|
||||
uartPort = <UART_NUM_1>;
|
||||
i2cPort = <I2C_NUM_1>;
|
||||
i2cClockFrequency = <400000>;
|
||||
};
|
||||
|
||||
display_spi: spi0 {
|
||||
@ -68,12 +71,4 @@
|
||||
pin-data-out = <&gpio0 42 GPIO_FLAG_NONE>;
|
||||
pin-data-in = <&gpio0 46 GPIO_FLAG_NONE>;
|
||||
};
|
||||
|
||||
uart_port_a: uart1 {
|
||||
compatible = "espressif,esp32-uart";
|
||||
status = "disabled";
|
||||
port = <UART_NUM_1>;
|
||||
pin-tx = <&gpio0 1 GPIO_FLAG_NONE>;
|
||||
pin-rx = <&gpio0 2 GPIO_FLAG_NONE>;
|
||||
};
|
||||
};
|
||||
|
||||
@ -3,6 +3,7 @@
|
||||
#include <tactility/bindings/root.h>
|
||||
#include <tactility/bindings/esp32_ble.h>
|
||||
#include <tactility/bindings/esp32_gpio.h>
|
||||
#include <tactility/bindings/esp32_grove.h>
|
||||
#include <tactility/bindings/esp32_i2c.h>
|
||||
#include <tactility/bindings/esp32_i2s.h>
|
||||
#include <tactility/bindings/esp32_spi.h>
|
||||
@ -22,12 +23,14 @@
|
||||
gpio-count = <49>;
|
||||
};
|
||||
|
||||
i2c_port_a {
|
||||
compatible = "espressif,esp32-i2c";
|
||||
port = <I2C_NUM_0>;
|
||||
clock-frequency = <400000>;
|
||||
pin-sda = <&gpio0 2 GPIO_FLAG_NONE>;
|
||||
pin-scl = <&gpio0 1 GPIO_FLAG_NONE>;
|
||||
port_a: grove0 {
|
||||
compatible = "espressif,esp32-grove";
|
||||
defaultMode = <GROVE_MODE_I2C>;
|
||||
pinSdaRx = <&gpio0 2 GPIO_FLAG_NONE>;
|
||||
pinSclTx = <&gpio0 1 GPIO_FLAG_NONE>;
|
||||
uartPort = <UART_NUM_1>;
|
||||
i2cPort = <I2C_NUM_0>;
|
||||
i2cClockFrequency = <400000>;
|
||||
};
|
||||
|
||||
display_spi: spi0 {
|
||||
@ -55,12 +58,4 @@
|
||||
pin-data-out = <&gpio0 42 GPIO_FLAG_NONE>;
|
||||
pin-data-in = <&gpio0 46 GPIO_FLAG_NONE>;
|
||||
};
|
||||
|
||||
uart_port_a: uart1 {
|
||||
compatible = "espressif,esp32-uart";
|
||||
status = "disabled";
|
||||
port = <UART_NUM_1>;
|
||||
pin-tx = <&gpio0 1 GPIO_FLAG_NONE>;
|
||||
pin-rx = <&gpio0 2 GPIO_FLAG_NONE>;
|
||||
};
|
||||
};
|
||||
|
||||
@ -1,10 +1,11 @@
|
||||
#include <Axp192.h>
|
||||
#include <tactility/device.h>
|
||||
|
||||
static std::shared_ptr<Axp192> axp192 = nullptr;
|
||||
|
||||
std::shared_ptr<Axp192> createAxp192() {
|
||||
assert(axp192 == nullptr);
|
||||
auto configuration = std::make_unique<Axp192::Configuration>(I2C_NUM_0);
|
||||
auto configuration = std::make_unique<Axp192::Configuration>(device_find_by_name("i2c_internal"));
|
||||
axp192 = std::make_shared<Axp192>(std::move(configuration));
|
||||
return axp192;
|
||||
}
|
||||
|
||||
@ -2,6 +2,7 @@
|
||||
|
||||
#include <tactility/bindings/root.h>
|
||||
#include <tactility/bindings/esp32_gpio.h>
|
||||
#include <tactility/bindings/esp32_grove.h>
|
||||
#include <tactility/bindings/esp32_i2c.h>
|
||||
#include <tactility/bindings/esp32_i2s.h>
|
||||
#include <tactility/bindings/esp32_spi.h>
|
||||
@ -37,12 +38,14 @@
|
||||
};
|
||||
};
|
||||
|
||||
i2c_port_a {
|
||||
compatible = "espressif,esp32-i2c";
|
||||
port = <I2C_NUM_1>;
|
||||
clock-frequency = <400000>;
|
||||
pin-sda = <&gpio0 32 GPIO_FLAG_NONE>;
|
||||
pin-scl = <&gpio0 33 GPIO_FLAG_NONE>;
|
||||
port_a: grove0 {
|
||||
compatible = "espressif,esp32-grove";
|
||||
defaultMode = <GROVE_MODE_I2C>;
|
||||
pinSdaRx = <&gpio0 32 GPIO_FLAG_NONE>;
|
||||
pinSclTx = <&gpio0 33 GPIO_FLAG_NONE>;
|
||||
uartPort = <UART_NUM_1>;
|
||||
i2cPort = <I2C_NUM_1>;
|
||||
i2cClockFrequency = <400000>;
|
||||
};
|
||||
|
||||
spi0 {
|
||||
@ -63,12 +66,4 @@
|
||||
pin-data-out = <&gpio0 2 GPIO_FLAG_NONE>;
|
||||
pin-data-in = <&gpio0 34 GPIO_FLAG_NONE>;
|
||||
};
|
||||
|
||||
uart_port_a: uart1 {
|
||||
compatible = "espressif,esp32-uart";
|
||||
status = "disabled";
|
||||
port = <UART_NUM_1>;
|
||||
pin-tx = <&gpio0 33 GPIO_FLAG_NONE>;
|
||||
pin-rx = <&gpio0 32 GPIO_FLAG_NONE>;
|
||||
};
|
||||
};
|
||||
|
||||
@ -146,8 +146,9 @@ bool initPowerControl() {
|
||||
bool initBoot() {
|
||||
LOGGER.info("initBoot()");
|
||||
|
||||
axp2101 = std::make_shared<Axp2101>(I2C_NUM_0);
|
||||
aw9523 = std::make_shared<Aw9523>(I2C_NUM_0);
|
||||
auto controller = device_find_by_name("i2c_internal");
|
||||
axp2101 = std::make_shared<Axp2101>(controller);
|
||||
aw9523 = std::make_shared<Aw9523>(controller);
|
||||
|
||||
return initPowerControl() && initGpioExpander();
|
||||
}
|
||||
@ -3,6 +3,7 @@
|
||||
#include <tactility/bindings/root.h>
|
||||
#include <tactility/bindings/esp32_ble.h>
|
||||
#include <tactility/bindings/esp32_gpio.h>
|
||||
#include <tactility/bindings/esp32_grove.h>
|
||||
#include <tactility/bindings/esp32_i2c.h>
|
||||
#include <tactility/bindings/esp32_i2s.h>
|
||||
#include <tactility/bindings/esp32_spi.h>
|
||||
@ -42,30 +43,34 @@
|
||||
};
|
||||
};
|
||||
|
||||
i2c_port_a {
|
||||
compatible = "espressif,esp32-i2c";
|
||||
port = <I2C_NUM_1>;
|
||||
clock-frequency = <400000>;
|
||||
pin-sda = <&gpio0 2 GPIO_FLAG_NONE>;
|
||||
pin-scl = <&gpio0 1 GPIO_FLAG_NONE>;
|
||||
port_a: grove0 {
|
||||
compatible = "espressif,esp32-grove";
|
||||
defaultMode = <GROVE_MODE_I2C>;
|
||||
pinSdaRx = <&gpio0 2 GPIO_FLAG_NONE>;
|
||||
pinSclTx = <&gpio0 1 GPIO_FLAG_NONE>;
|
||||
uartPort = <UART_NUM_1>;
|
||||
i2cPort = <I2C_NUM_1>;
|
||||
i2cClockFrequency = <400000>;
|
||||
};
|
||||
|
||||
i2c_port_b {
|
||||
compatible = "espressif,esp32-i2c";
|
||||
status = "disabled";
|
||||
port = <I2C_NUM_1>;
|
||||
clock-frequency = <400000>;
|
||||
pin-sda = <&gpio0 9 GPIO_FLAG_NONE>;
|
||||
pin-scl = <&gpio0 8 GPIO_FLAG_NONE>;
|
||||
port_b: grove1 {
|
||||
compatible = "espressif,esp32-grove";
|
||||
defaultMode = <GROVE_MODE_UART>;
|
||||
pinSdaRx = <&gpio0 9 GPIO_FLAG_NONE>;
|
||||
pinSclTx = <&gpio0 8 GPIO_FLAG_NONE>;
|
||||
uartPort = <UART_NUM_1>;
|
||||
i2cPort = <I2C_NUM_1>;
|
||||
i2cClockFrequency = <400000>;
|
||||
};
|
||||
|
||||
i2c_port_c {
|
||||
compatible = "espressif,esp32-i2c";
|
||||
status = "disabled";
|
||||
port = <I2C_NUM_1>;
|
||||
clock-frequency = <400000>;
|
||||
pin-sda = <&gpio0 18 GPIO_FLAG_NONE>;
|
||||
pin-scl = <&gpio0 17 GPIO_FLAG_NONE>;
|
||||
port_c: grove2 {
|
||||
compatible = "espressif,esp32-grove";
|
||||
defaultMode = <GROVE_MODE_UART>;
|
||||
pinSdaRx = <&gpio0 17 GPIO_FLAG_NONE>;
|
||||
pinSclTx = <&gpio0 18 GPIO_FLAG_NONE>;
|
||||
uartPort = <UART_NUM_2>;
|
||||
i2cPort = <I2C_NUM_1>;
|
||||
i2cClockFrequency = <400000>;
|
||||
};
|
||||
|
||||
spi0 {
|
||||
@ -89,12 +94,4 @@
|
||||
pin-data-in = <&gpio0 14 GPIO_FLAG_NONE>;
|
||||
pin-mclk = <&gpio0 0 GPIO_FLAG_NONE>;
|
||||
};
|
||||
|
||||
uart_port_a: uart1 {
|
||||
compatible = "espressif,esp32-uart";
|
||||
status = "disabled";
|
||||
port = <UART_NUM_1>;
|
||||
pin-tx = <&gpio0 1 GPIO_FLAG_NONE>;
|
||||
pin-rx = <&gpio0 2 GPIO_FLAG_NONE>;
|
||||
};
|
||||
};
|
||||
|
||||
@ -231,7 +231,7 @@ bool initBoot() {
|
||||
}
|
||||
|
||||
// Keep Axp2101 C++ wrapper alive for Axp2101Power (backlight + battery)
|
||||
axp2101 = std::make_shared<Axp2101>(I2C_NUM_0);
|
||||
axp2101 = std::make_shared<Axp2101>(i2c);
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
@ -67,30 +67,43 @@
|
||||
// TODO: BMM150 magnetometer @ 0x10 — accessible only via BMI270 aux I2C
|
||||
};
|
||||
|
||||
i2c_port_a {
|
||||
compatible = "espressif,esp32-i2c";
|
||||
port = <I2C_NUM_1>;
|
||||
clock-frequency = <400000>;
|
||||
pin-sda = <&gpio0 2 GPIO_FLAG_NONE>;
|
||||
pin-scl = <&gpio0 1 GPIO_FLAG_NONE>;
|
||||
// TODO: Servo UART (SCS9009, 1 Mbaud) — TX=GPIO6, RX=GPIO7
|
||||
uart_port_a: uart1 {
|
||||
compatible = "espressif,esp32-uart";
|
||||
status = "disabled";
|
||||
port = <UART_NUM_1>;
|
||||
pin-tx = <&gpio0 6 GPIO_FLAG_NONE>;
|
||||
pin-rx = <&gpio0 7 GPIO_FLAG_NONE>;
|
||||
};
|
||||
|
||||
i2c_port_b {
|
||||
compatible = "espressif,esp32-i2c";
|
||||
status = "disabled";
|
||||
port = <I2C_NUM_1>;
|
||||
clock-frequency = <400000>;
|
||||
pin-sda = <&gpio0 9 GPIO_FLAG_NONE>;
|
||||
pin-scl = <&gpio0 8 GPIO_FLAG_NONE>;
|
||||
port_a: grove0 {
|
||||
compatible = "espressif,esp32-grove";
|
||||
defaultMode = <GROVE_MODE_I2C>;
|
||||
pinSdaRx = <&gpio0 2 GPIO_FLAG_NONE>;
|
||||
pinSclTx = <&gpio0 1 GPIO_FLAG_NONE>;
|
||||
uartPort = <UART_NUM_2>;
|
||||
i2cPort = <I2C_NUM_1>;
|
||||
i2cClockFrequency = <400000>;
|
||||
};
|
||||
|
||||
i2c_port_c {
|
||||
compatible = "espressif,esp32-i2c";
|
||||
status = "disabled";
|
||||
port = <I2C_NUM_1>;
|
||||
clock-frequency = <400000>;
|
||||
pin-sda = <&gpio0 18 GPIO_FLAG_NONE>;
|
||||
pin-scl = <&gpio0 17 GPIO_FLAG_NONE>;
|
||||
port_b: grove1 {
|
||||
compatible = "espressif,esp32-grove";
|
||||
defaultMode = <GROVE_MODE_UART>;
|
||||
pinSdaRx = <&gpio0 9 GPIO_FLAG_NONE>;
|
||||
pinSclTx = <&gpio0 8 GPIO_FLAG_NONE>;
|
||||
uartPort = <UART_NUM_2>;
|
||||
i2cPort = <I2C_NUM_1>;
|
||||
i2cClockFrequency = <400000>;
|
||||
};
|
||||
|
||||
port_c: grove2 {
|
||||
compatible = "espressif,esp32-grove";
|
||||
defaultMode = <GROVE_MODE_DISABLED>;
|
||||
pinSdaRx = <&gpio0 17 GPIO_FLAG_NONE>;
|
||||
pinSclTx = <&gpio0 18 GPIO_FLAG_NONE>;
|
||||
uartPort = <UART_NUM_2>;
|
||||
i2cPort = <I2C_NUM_1>;
|
||||
i2cClockFrequency = <400000>;
|
||||
};
|
||||
|
||||
spi0 {
|
||||
@ -111,13 +124,4 @@
|
||||
pin-data-in = <&gpio0 14 GPIO_FLAG_NONE>;
|
||||
pin-mclk = <&gpio0 0 GPIO_FLAG_NONE>;
|
||||
};
|
||||
|
||||
// TODO: Servo UART (SCS9009, 1 Mbaud) — TX=GPIO6, RX=GPIO7
|
||||
uart_port_a: uart1 {
|
||||
compatible = "espressif,esp32-uart";
|
||||
status = "disabled";
|
||||
port = <UART_NUM_1>;
|
||||
pin-tx = <&gpio0 1 GPIO_FLAG_NONE>;
|
||||
pin-rx = <&gpio0 2 GPIO_FLAG_NONE>;
|
||||
};
|
||||
};
|
||||
|
||||
@ -1,10 +1,11 @@
|
||||
#include <Axp192.h>
|
||||
#include <tactility/device.h>
|
||||
|
||||
static std::shared_ptr<Axp192> axp192 = nullptr;
|
||||
|
||||
std::shared_ptr<Axp192> createAxp192() {
|
||||
assert(axp192 == nullptr);
|
||||
auto configuration = std::make_unique<Axp192::Configuration>(I2C_NUM_0);
|
||||
auto configuration = std::make_unique<Axp192::Configuration>(device_find_by_name("i2c_internal"));
|
||||
axp192 = std::make_shared<Axp192>(std::move(configuration));
|
||||
return axp192;
|
||||
}
|
||||
|
||||
@ -1,4 +1,5 @@
|
||||
#include "UnPhoneFeatures.h"
|
||||
#include <tactility/device.h>
|
||||
#include <Tactility/Logger.h>
|
||||
#include <Tactility/LogMessages.h>
|
||||
#include <Tactility/Preferences.h>
|
||||
@ -160,7 +161,7 @@ static bool unPhonePowerOn() {
|
||||
bootStats.printInfo();
|
||||
bootStats.notifyBootStart();
|
||||
|
||||
bq24295 = std::make_shared<Bq24295>(I2C_NUM_0);
|
||||
bq24295 = std::make_shared<Bq24295>(device_find_by_name("i2c_internal"));
|
||||
|
||||
unPhoneFeatures = std::make_shared<UnPhoneFeatures>(bq24295);
|
||||
|
||||
|
||||
@ -8,7 +8,7 @@ class Aw9523 : public tt::hal::i2c::I2cDevice {
|
||||
|
||||
public:
|
||||
|
||||
explicit Aw9523(i2c_port_t port) : I2cDevice(port, AW9523_ADDRESS) {}
|
||||
explicit Aw9523(::Device* controller) : I2cDevice(controller, AW9523_ADDRESS) {}
|
||||
|
||||
std::string getName() const final { return "AW9523"; }
|
||||
std::string getDescription() const final { return "GPIO expander with LED driver and I2C interface."; }
|
||||
|
||||
@ -1,6 +1,7 @@
|
||||
#pragma once
|
||||
|
||||
#include <axp192/axp192.h>
|
||||
#include <tactility/device.h>
|
||||
#include <Tactility/hal/power/PowerDevice.h>
|
||||
#include <Tactility/hal/i2c/I2c.h>
|
||||
|
||||
@ -14,7 +15,7 @@ class Axp192 final : public tt::hal::power::PowerDevice {
|
||||
public:
|
||||
|
||||
struct Configuration {
|
||||
i2c_port_t port;
|
||||
::Device* controller;
|
||||
TickType_t readTimeout = 50 / portTICK_PERIOD_MS;
|
||||
TickType_t writeTimeout = 50 / portTICK_PERIOD_MS;
|
||||
};
|
||||
|
||||
@ -1,10 +1,11 @@
|
||||
#include "Axp192.h"
|
||||
#include <tactility/drivers/i2c_controller.h>
|
||||
|
||||
constexpr auto TAG = "Axp192Power";
|
||||
|
||||
int32_t Axp192::i2cRead(void* handle, uint8_t address, uint8_t reg, uint8_t* buffer, uint16_t size) {
|
||||
const auto* device = static_cast<Axp192*>(handle);
|
||||
if (tt::hal::i2c::masterReadRegister(device->configuration->port, address, reg, buffer, size, device->configuration->readTimeout)) {
|
||||
if (i2c_controller_read_register(device->configuration->controller, address, reg, buffer, size, device->configuration->readTimeout) == ERROR_NONE) {
|
||||
return AXP192_OK;
|
||||
} else {
|
||||
return 1;
|
||||
@ -13,7 +14,7 @@ int32_t Axp192::i2cRead(void* handle, uint8_t address, uint8_t reg, uint8_t* buf
|
||||
|
||||
int32_t Axp192::i2cWrite(void* handle, uint8_t address, uint8_t reg, const uint8_t* buffer, uint16_t size) {
|
||||
const auto* device = static_cast<Axp192*>(handle);
|
||||
if (tt::hal::i2c::masterWriteRegister(device->configuration->port, address, reg, buffer, size, device->configuration->writeTimeout)) {
|
||||
if (i2c_controller_write_register(device->configuration->controller, address, reg, buffer, size, device->configuration->writeTimeout) == ERROR_NONE) {
|
||||
return AXP192_OK;
|
||||
} else {
|
||||
return 1;
|
||||
|
||||
@ -54,5 +54,5 @@ bool Axp2101::getVBusVoltage(float& out) const {
|
||||
}
|
||||
|
||||
bool Axp2101::setRegisters(uint8_t* bytePairs, size_t bytePairsSize) const {
|
||||
return tt::hal::i2c::masterWriteRegisterArray(port, address, bytePairs, bytePairsSize, DEFAULT_TIMEOUT);
|
||||
return i2c_controller_write_register_array(controller, address, bytePairs, bytePairsSize, DEFAULT_TIMEOUT) == ERROR_NONE;
|
||||
}
|
||||
|
||||
@ -19,7 +19,7 @@ public:
|
||||
CHARGE_STATUS_STANDBY = 0b00
|
||||
};
|
||||
|
||||
explicit Axp2101(i2c_port_t port) : I2cDevice(port, AXP2101_ADDRESS) {}
|
||||
explicit Axp2101(::Device* controller) : I2cDevice(controller, AXP2101_ADDRESS) {}
|
||||
|
||||
std::string getName() const override { return "AXP2101"; }
|
||||
std::string getDescription() const override { return "Power management with I2C interface."; }
|
||||
|
||||
@ -22,7 +22,7 @@ public:
|
||||
Enabled160s = 0b110000
|
||||
};
|
||||
|
||||
explicit Bq24295(i2c_port_t port) : I2cDevice(port, BQ24295_ADDRESS) {}
|
||||
explicit Bq24295(::Device* controller) : I2cDevice(controller, BQ24295_ADDRESS) {}
|
||||
|
||||
bool getWatchDogTimer(WatchDogTimer& out) const;
|
||||
bool setWatchDogTimer(WatchDogTimer in) const;
|
||||
|
||||
@ -8,7 +8,7 @@ class Bq25896 final : public tt::hal::i2c::I2cDevice {
|
||||
|
||||
public:
|
||||
|
||||
explicit Bq25896(i2c_port_t port) : I2cDevice(port, BQ25896_ADDRESS) {
|
||||
explicit Bq25896(::Device* controller) : I2cDevice(controller, BQ25896_ADDRESS) {
|
||||
powerOn();
|
||||
}
|
||||
|
||||
|
||||
@ -89,7 +89,7 @@ public:
|
||||
|
||||
std::string getDescription() const override { return "I2C-controlled CEDV battery fuel gauge"; }
|
||||
|
||||
explicit Bq27220(i2c_port_t port) : I2cDevice(port, BQ27220_ADDRESS), accessKey(0xFFFFFFFF) {}
|
||||
explicit Bq27220(::Device* controller) : I2cDevice(controller, BQ27220_ADDRESS), accessKey(0xFFFFFFFF) {}
|
||||
|
||||
bool configureCapacity(uint16_t designCapacity, uint16_t fullChargeCapacity);
|
||||
bool getVoltage(uint16_t &value);
|
||||
|
||||
@ -5,7 +5,7 @@
|
||||
|
||||
static const auto LOGGER = tt::Logger("DRV2605");
|
||||
|
||||
Drv2605::Drv2605(i2c_port_t port, bool autoPlayStartupBuzz) : I2cDevice(port, ADDRESS), autoPlayStartupBuzz(autoPlayStartupBuzz) {
|
||||
Drv2605::Drv2605(::Device* controller, bool autoPlayStartupBuzz) : I2cDevice(controller, ADDRESS), autoPlayStartupBuzz(autoPlayStartupBuzz) {
|
||||
check(init(), "Initialize DRV2605");
|
||||
|
||||
if (autoPlayStartupBuzz) {
|
||||
|
||||
@ -62,7 +62,7 @@ class Drv2605 : public tt::hal::i2c::I2cDevice {
|
||||
|
||||
public:
|
||||
|
||||
explicit Drv2605(i2c_port_t port, bool autoPlayStartupBuzz = true);
|
||||
explicit Drv2605(::Device* controller, bool autoPlayStartupBuzz = true);
|
||||
|
||||
std::string getName() const final { return "DRV2605"; }
|
||||
std::string getDescription() const final { return "Haptic driver for ERM/LRA with waveform library & auto-resonance tracking"; }
|
||||
|
||||
@ -2,6 +2,7 @@
|
||||
|
||||
#include <Tactility/hal/touch/TouchDevice.h>
|
||||
#include <Tactility/TactilityCore.h>
|
||||
#include <tactility/device.h>
|
||||
#include <driver/i2c.h>
|
||||
|
||||
#include <EspLcdTouch.h>
|
||||
@ -14,7 +15,7 @@ public:
|
||||
public:
|
||||
|
||||
Configuration(
|
||||
i2c_port_t port,
|
||||
::Device* controller,
|
||||
uint16_t xMax,
|
||||
uint16_t yMax,
|
||||
bool swapXy = false,
|
||||
@ -24,7 +25,7 @@ public:
|
||||
gpio_num_t pinInterrupt = GPIO_NUM_NC,
|
||||
unsigned int pinResetLevel = 0,
|
||||
unsigned int pinInterruptLevel = 0
|
||||
) : port(port),
|
||||
) : controller(controller),
|
||||
xMax(xMax),
|
||||
yMax(yMax),
|
||||
swapXy(swapXy),
|
||||
@ -36,7 +37,7 @@ public:
|
||||
pinInterruptLevel(pinInterruptLevel)
|
||||
{}
|
||||
|
||||
i2c_port_t port;
|
||||
::Device* controller;
|
||||
uint16_t xMax;
|
||||
uint16_t yMax;
|
||||
bool swapXy;
|
||||
|
||||
@ -45,7 +45,7 @@ public:
|
||||
|
||||
std::string getDescription() const final { return "I2C-controlled keyboard scan IC"; }
|
||||
|
||||
explicit Tca8418(i2c_port_t port) : I2cDevice(port, TCA8418_ADDRESS) {
|
||||
explicit Tca8418(::Device* controller) : I2cDevice(controller, TCA8418_ADDRESS) {
|
||||
delta_micros = 0;
|
||||
last_update_micros = 0;
|
||||
this_update_micros = 0;
|
||||
|
||||
@ -7,14 +7,14 @@ properties:
|
||||
type: int
|
||||
required: true
|
||||
description: "One of enum Esp32GroveMode"
|
||||
pinSclTx:
|
||||
type: phandle-array
|
||||
required: true
|
||||
description: SCL (I2C) or TX (UART) pin
|
||||
pinSdaRx:
|
||||
type: phandle-array
|
||||
required: true
|
||||
description: SDA (I2C) or RX (UART) pin
|
||||
pinSclTx:
|
||||
type: phandle-array
|
||||
required: true
|
||||
description: SCL (I2C) or TX (UART) pin
|
||||
uartPort:
|
||||
type: int
|
||||
required: true
|
||||
|
||||
@ -12,8 +12,8 @@ extern "C" {
|
||||
|
||||
struct Esp32GroveConfig {
|
||||
enum GroveMode defaultMode;
|
||||
struct GpioPinSpec pinSclTx;
|
||||
struct GpioPinSpec pinSdaRx;
|
||||
struct GpioPinSpec pinSclTx;
|
||||
uart_port_t uartPort;
|
||||
i2c_port_t i2cPort;
|
||||
uint32_t i2cClockFrequency;
|
||||
|
||||
@ -1,16 +1,16 @@
|
||||
// SPDX-License-Identifier: Apache-2.0
|
||||
#include <tactility/check.h>
|
||||
#include <tactility/device.h>
|
||||
#include <tactility/driver.h>
|
||||
#include <tactility/drivers/esp32_grove.h>
|
||||
|
||||
#include "../../../../TactilityKernel/include/tactility/check.h"
|
||||
#include <tactility/drivers/esp32_i2c.h>
|
||||
#include <tactility/drivers/esp32_i2c_master.h>
|
||||
#include <tactility/drivers/esp32_uart.h>
|
||||
#include <tactility/log.h>
|
||||
|
||||
#include <cstdio>
|
||||
#include <cstring>
|
||||
#include <new>
|
||||
#include <tactility/drivers/esp32_i2c.h>
|
||||
#include <tactility/drivers/esp32_uart.h>
|
||||
#include <tactility/log.h>
|
||||
|
||||
#define TAG "esp32_grove"
|
||||
|
||||
@ -54,7 +54,7 @@ static error_t stop_child(Device* device) {
|
||||
if (data->current_mode == GROVE_MODE_UART) {
|
||||
delete static_cast<Esp32UartConfig*>(data->child_config);
|
||||
} else if (data->current_mode == GROVE_MODE_I2C) {
|
||||
delete static_cast<Esp32I2cConfig*>(data->child_config);
|
||||
delete static_cast<Esp32I2cMasterConfig*>(data->child_config);
|
||||
}
|
||||
data->child_config = nullptr;
|
||||
}
|
||||
@ -89,13 +89,15 @@ static error_t start_child(Device* device, GroveMode mode) {
|
||||
data->child_device = nullptr;
|
||||
return ERROR_OUT_OF_MEMORY;
|
||||
}
|
||||
std::snprintf(data->child_name, name_len, "%s_child", device->name);
|
||||
data->child_device->name = data->child_name;
|
||||
data->child_device->parent = device;
|
||||
|
||||
data->child_device->parent = device;
|
||||
const char* compatible = nullptr;
|
||||
|
||||
if (mode == GROVE_MODE_UART) {
|
||||
// Device name
|
||||
std::snprintf(data->child_name, name_len, "%s_uart", device->name);
|
||||
data->child_device->name = data->child_name;
|
||||
// Device config
|
||||
auto* uart_cfg = new(std::nothrow) struct Esp32UartConfig();
|
||||
if (!uart_cfg) {
|
||||
delete[] data->child_name;
|
||||
@ -114,7 +116,11 @@ static error_t start_child(Device* device, GroveMode mode) {
|
||||
compatible = "espressif,esp32-uart";
|
||||
LOG_I(TAG, "%s: starting UART mode on port %d", device->name, (int)uart_cfg->port);
|
||||
} else if (mode == GROVE_MODE_I2C) {
|
||||
auto* i2c_cfg = new(std::nothrow) struct Esp32I2cConfig();
|
||||
// Device name
|
||||
std::snprintf(data->child_name, name_len, "%s_i2c", device->name);
|
||||
data->child_device->name = data->child_name;
|
||||
// Device config
|
||||
auto* i2c_cfg = new (std::nothrow) struct Esp32I2cMasterConfig();
|
||||
if (!i2c_cfg) {
|
||||
delete[] data->child_name;
|
||||
data->child_name = nullptr;
|
||||
@ -122,18 +128,21 @@ static error_t start_child(Device* device, GroveMode mode) {
|
||||
data->child_device = nullptr;
|
||||
return ERROR_OUT_OF_MEMORY;
|
||||
}
|
||||
std::memset(i2c_cfg, 0, sizeof(Esp32I2cConfig));
|
||||
i2c_cfg->port = config->i2cPort;
|
||||
std::memset(i2c_cfg, 0, sizeof(Esp32I2cMasterConfig));
|
||||
i2c_cfg->port = static_cast<i2c_port_num_t>(config->i2cPort);
|
||||
i2c_cfg->clockFrequency = config->i2cClockFrequency;
|
||||
i2c_cfg->pinSda = config->pinSdaRx;
|
||||
i2c_cfg->pinScl = config->pinSclTx;
|
||||
i2c_cfg->clkSource = 0; // Default
|
||||
data->child_config = i2c_cfg;
|
||||
compatible = "espressif,esp32-i2c";
|
||||
LOG_I(TAG, "%s: starting I2C mode on port %d", device->name, (int)i2c_cfg->port);
|
||||
compatible = "espressif,esp32-i2c-master";
|
||||
LOG_I(TAG, "%s: starting I2C mode on port %d", device->name, (int)config->i2cPort);
|
||||
} else {
|
||||
LOG_E(TAG, "%s: unknown mode %d", device->name, mode);
|
||||
delete[] data->child_name;
|
||||
data->child_name = nullptr;
|
||||
if (data->child_name != nullptr) {
|
||||
delete[] data->child_name;
|
||||
data->child_name = nullptr;
|
||||
}
|
||||
delete data->child_device;
|
||||
data->child_device = nullptr;
|
||||
return ERROR_INVALID_ARGUMENT;
|
||||
@ -154,6 +163,7 @@ static error_t start_child(Device* device, GroveMode mode) {
|
||||
|
||||
static error_t start_device(Device* device) {
|
||||
const auto* config = GET_CONFIG(device);
|
||||
|
||||
auto* data = new(std::nothrow) Esp32GroveInternal();
|
||||
if (!data) return ERROR_OUT_OF_MEMORY;
|
||||
device_set_driver_data(device, data);
|
||||
|
||||
@ -1,6 +1,7 @@
|
||||
#pragma once
|
||||
|
||||
#include <tactility/hal/Device.h>
|
||||
#include <tactility/drivers/i2c_controller.h>
|
||||
#include "I2c.h"
|
||||
|
||||
namespace tt::hal::i2c {
|
||||
@ -15,7 +16,7 @@ class I2cDevice : public Device {
|
||||
|
||||
protected:
|
||||
|
||||
i2c_port_t port;
|
||||
::Device* controller;
|
||||
uint8_t address;
|
||||
|
||||
static constexpr TickType_t DEFAULT_TIMEOUT = 1000 / portTICK_PERIOD_MS;
|
||||
@ -36,11 +37,11 @@ protected:
|
||||
|
||||
public:
|
||||
|
||||
explicit I2cDevice(i2c_port_t port, uint32_t address) : port(port), address(address) {}
|
||||
explicit I2cDevice(::Device* controller, uint32_t address) : controller(controller), address(address) {}
|
||||
|
||||
Type getType() const override { return Type::I2c; }
|
||||
|
||||
i2c_port_t getPort() const { return port; }
|
||||
::Device* getController() const { return controller; }
|
||||
|
||||
uint8_t getAddress() const { return address; }
|
||||
};
|
||||
|
||||
@ -3,12 +3,14 @@
|
||||
#include <string>
|
||||
#include <cstdint>
|
||||
|
||||
struct Device;
|
||||
|
||||
namespace tt::app::i2cscanner {
|
||||
|
||||
std::string getAddressText(uint8_t address);
|
||||
|
||||
std::string getPortNamesForDropdown();
|
||||
|
||||
bool getActivePortAtIndex(int32_t index, int32_t& out);
|
||||
bool getActivePortAtIndex(int32_t index, struct Device** out);
|
||||
|
||||
}
|
||||
|
||||
@ -1,7 +1,8 @@
|
||||
#include "Tactility/app/i2cscanner/I2cHelpers.h"
|
||||
|
||||
#include <Tactility/StringUtils.h>
|
||||
#include <Tactility/hal/i2c/I2c.h>
|
||||
|
||||
#include <tactility/drivers/i2c_controller.h>
|
||||
|
||||
#include <iomanip>
|
||||
#include <vector>
|
||||
@ -19,31 +20,36 @@ std::string getAddressText(uint8_t address) {
|
||||
|
||||
std::string getPortNamesForDropdown() {
|
||||
std::vector<std::string> config_names;
|
||||
for (int port = 0; port < I2C_NUM_MAX; ++port) {
|
||||
auto native_port = static_cast<i2c_port_t>(port);
|
||||
if (hal::i2c::isStarted(native_port)) {
|
||||
auto* name = hal::i2c::getName(native_port);
|
||||
if (name != nullptr) {
|
||||
config_names.push_back(name);
|
||||
}
|
||||
device_for_each_of_type(&I2C_CONTROLLER_TYPE, &config_names, [](auto* device, auto* context) {
|
||||
auto* names = static_cast<std::vector<std::string>*>(context);
|
||||
if (device_is_ready(device)) {
|
||||
names->push_back(device->name);
|
||||
}
|
||||
}
|
||||
return true;
|
||||
});
|
||||
return string::join(config_names, "\n");
|
||||
}
|
||||
|
||||
bool getActivePortAtIndex(int32_t index, int32_t& out) {
|
||||
int current_index = -1;
|
||||
for (int port = 0; port < I2C_NUM_MAX; ++port) {
|
||||
auto native_port = static_cast<i2c_port_t>(port);
|
||||
if (hal::i2c::isStarted(native_port)) {
|
||||
current_index++;
|
||||
if (current_index == index) {
|
||||
out = port;
|
||||
return true;
|
||||
bool getActivePortAtIndex(int32_t index, struct Device** out) {
|
||||
struct Context {
|
||||
int32_t targetIndex;
|
||||
int32_t currentIndex;
|
||||
struct Device* foundDevice;
|
||||
} context = { index, 0, nullptr };
|
||||
|
||||
device_for_each_of_type(&I2C_CONTROLLER_TYPE, &context, [](auto* device, auto* ctx) {
|
||||
auto* c = static_cast<Context*>(ctx);
|
||||
if (device_is_ready(device)) {
|
||||
if (c->currentIndex == c->targetIndex) {
|
||||
c->foundDevice = device;
|
||||
return false;
|
||||
}
|
||||
c->currentIndex++;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
return true;
|
||||
});
|
||||
*out = context.foundDevice;
|
||||
return context.foundDevice != nullptr;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
@ -3,7 +3,7 @@
|
||||
|
||||
#include <Tactility/Assets.h>
|
||||
#include <Tactility/app/AppContext.h>
|
||||
#include <Tactility/hal/i2c/I2cDevice.h>
|
||||
#include <tactility/drivers/i2c_controller.h>
|
||||
#include <Tactility/Logger.h>
|
||||
#include <Tactility/LogMessages.h>
|
||||
#include <Tactility/lvgl/LvglSync.h>
|
||||
@ -33,7 +33,7 @@ class I2cScannerApp final : public App {
|
||||
std::unique_ptr<Timer> scanTimer = nullptr;
|
||||
// State
|
||||
ScanState scanState = ScanStateInitial;
|
||||
i2c_port_t port = I2C_NUM_0;
|
||||
struct Device* portDevice = nullptr;
|
||||
std::vector<uint8_t> scannedAddresses;
|
||||
// Widgets
|
||||
lv_obj_t* scanButtonLabelWidget = nullptr;
|
||||
@ -54,7 +54,7 @@ class I2cScannerApp final : public App {
|
||||
void onScanTimer();
|
||||
|
||||
bool shouldStopScanTimer();
|
||||
bool getPort(i2c_port_t* outPort);
|
||||
bool getPort(struct Device** outPort);
|
||||
bool addAddressToList(uint8_t address);
|
||||
bool hasScanThread();
|
||||
void startScanning();
|
||||
@ -140,8 +140,10 @@ void I2cScannerApp::onShow(AppContext& app, lv_obj_t* parent) {
|
||||
lv_obj_add_flag(scan_list, LV_OBJ_FLAG_HIDDEN);
|
||||
scanListWidget = scan_list;
|
||||
|
||||
int32_t first_port;
|
||||
if (getActivePortAtIndex(0, first_port)) {
|
||||
struct Device* dummy;
|
||||
if (getActivePortAtIndex(selected_bus, &dummy)) {
|
||||
selectBus(selected_bus);
|
||||
} else if (getActivePortAtIndex(0, &dummy)) {
|
||||
lv_dropdown_set_selected(port_dropdown, 0);
|
||||
selectBus(0);
|
||||
}
|
||||
@ -184,9 +186,9 @@ void I2cScannerApp::onPressScanCallback(lv_event_t* event) {
|
||||
|
||||
// endregion Callbacks
|
||||
|
||||
bool I2cScannerApp::getPort(i2c_port_t* outPort) {
|
||||
bool I2cScannerApp::getPort(struct Device** outPort) {
|
||||
if (mutex.lock(100 / portTICK_PERIOD_MS)) {
|
||||
*outPort = this->port;
|
||||
*outPort = this->portDevice;
|
||||
mutex.unlock();
|
||||
return true;
|
||||
} else {
|
||||
@ -219,21 +221,21 @@ bool I2cScannerApp::shouldStopScanTimer() {
|
||||
void I2cScannerApp::onScanTimer() {
|
||||
logger.info("Scan thread started");
|
||||
|
||||
i2c_port_t safe_port;
|
||||
struct Device* safe_port;
|
||||
if (!getPort(&safe_port)) {
|
||||
logger.error("Failed to get I2C port");
|
||||
onScanTimerFinished();
|
||||
return;
|
||||
}
|
||||
|
||||
if (!hal::i2c::isStarted(safe_port)) {
|
||||
if (!device_is_ready(safe_port)) {
|
||||
logger.error("I2C port not started");
|
||||
onScanTimerFinished();
|
||||
return;
|
||||
}
|
||||
|
||||
for (uint8_t address = 0; address < 128; ++address) {
|
||||
if (hal::i2c::masterHasDeviceAtAddress(safe_port, address, 10 / portTICK_PERIOD_MS)) {
|
||||
if (i2c_controller_has_device_at_address(safe_port, address, 10 / portTICK_PERIOD_MS) == ERROR_NONE) {
|
||||
logger.info("Found device at address 0x{:02X}", address);
|
||||
if (!shouldStopScanTimer()) {
|
||||
addAddressToList(address);
|
||||
@ -305,14 +307,14 @@ void I2cScannerApp::onSelectBus(lv_event_t* event) {
|
||||
}
|
||||
|
||||
void I2cScannerApp::selectBus(int32_t selected) {
|
||||
int32_t found_port;
|
||||
if (!getActivePortAtIndex(selected, found_port)) {
|
||||
struct Device* found_device;
|
||||
if (!getActivePortAtIndex(selected, &found_device)) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (mutex.lock(100 / portTICK_PERIOD_MS)) {
|
||||
scannedAddresses.clear();
|
||||
port = static_cast<i2c_port_t>(found_port);
|
||||
portDevice = found_device;
|
||||
scanState = ScanStateInitial;
|
||||
mutex.unlock();
|
||||
}
|
||||
@ -334,16 +336,6 @@ void I2cScannerApp::onPressScan(lv_event_t* event) {
|
||||
updateViews();
|
||||
}
|
||||
|
||||
static bool findDeviceName(const std::vector<std::shared_ptr<hal::i2c::I2cDevice>>& devices, i2c_port_t port, uint8_t address, std::string& outName) {
|
||||
for (auto& device : devices) {
|
||||
if (device->getPort() == port && device->getAddress() == address) {
|
||||
outName = device->getName();
|
||||
return true;
|
||||
}
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
void I2cScannerApp::updateViews() {
|
||||
if (mutex.lock(100 / portTICK_PERIOD_MS)) {
|
||||
if (scanState == ScanStateScanning) {
|
||||
@ -358,18 +350,10 @@ void I2cScannerApp::updateViews() {
|
||||
if (scanState == ScanStateStopped) {
|
||||
lv_obj_remove_flag(scanListWidget, LV_OBJ_FLAG_HIDDEN);
|
||||
|
||||
auto devices = hal::findDevices<hal::i2c::I2cDevice>(hal::Device::Type::I2c);
|
||||
|
||||
if (!scannedAddresses.empty()) {
|
||||
for (auto address: scannedAddresses) {
|
||||
std::string address_text = getAddressText(address);
|
||||
std::string device_name;
|
||||
if (findDeviceName(devices, port, address, device_name)) {
|
||||
auto text = std::format("{} - {}", address_text, device_name);
|
||||
lv_list_add_text(scanListWidget, text.c_str());
|
||||
} else {
|
||||
lv_list_add_text(scanListWidget, address_text.c_str());
|
||||
}
|
||||
lv_list_add_text(scanListWidget, address_text.c_str());
|
||||
}
|
||||
} else {
|
||||
lv_list_add_text(scanListWidget, "No devices found");
|
||||
|
||||
@ -5,24 +5,24 @@
|
||||
namespace tt::hal::i2c {
|
||||
|
||||
bool I2cDevice::read(uint8_t* data, size_t dataSize, TickType_t timeout) {
|
||||
return masterRead(port, address, data, dataSize, timeout);
|
||||
return i2c_controller_read(controller, address, data, dataSize, timeout) == ERROR_NONE;
|
||||
}
|
||||
|
||||
bool I2cDevice::write(const uint8_t* data, uint16_t dataSize, TickType_t timeout) {
|
||||
return masterWrite(port, address, data, dataSize, timeout);
|
||||
return i2c_controller_write(controller, address, data, dataSize, timeout) == ERROR_NONE;
|
||||
}
|
||||
|
||||
bool I2cDevice::writeRead(const uint8_t* writeData, size_t writeDataSize, uint8_t* readData, size_t readDataSize, TickType_t timeout) {
|
||||
return masterWriteRead(port, address, writeData, writeDataSize, readData, readDataSize, timeout);
|
||||
return i2c_controller_write_read(controller, address, writeData, writeDataSize, readData, readDataSize, timeout) == ERROR_NONE;
|
||||
}
|
||||
|
||||
bool I2cDevice::writeRegister(uint8_t reg, const uint8_t* data, uint16_t dataSize, TickType_t timeout) {
|
||||
return masterWriteRegister(port, address, reg, data, dataSize, timeout);
|
||||
return i2c_controller_write_register(controller, address, reg, data, dataSize, timeout) == ERROR_NONE;
|
||||
}
|
||||
|
||||
bool I2cDevice::readRegister12(uint8_t reg, float& out) const {
|
||||
std::uint8_t data[2] = {0};
|
||||
if (masterReadRegister(port, address, reg, data, 2, DEFAULT_TIMEOUT)) {
|
||||
if (i2c_controller_read_register(controller, address, reg, data, 2, DEFAULT_TIMEOUT) == ERROR_NONE) {
|
||||
out = (data[0] & 0x0F) << 8 | data[1];
|
||||
return true;
|
||||
} else {
|
||||
@ -32,7 +32,7 @@ bool I2cDevice::readRegister12(uint8_t reg, float& out) const {
|
||||
|
||||
bool I2cDevice::readRegister14(uint8_t reg, float& out) const {
|
||||
std::uint8_t data[2] = {0};
|
||||
if (masterReadRegister(port, address, reg, data, 2, DEFAULT_TIMEOUT)) {
|
||||
if (i2c_controller_read_register(controller, address, reg, data, 2, DEFAULT_TIMEOUT) == ERROR_NONE) {
|
||||
out = (data[0] & 0x3F) << 8 | data[1];
|
||||
return true;
|
||||
} else {
|
||||
@ -42,7 +42,7 @@ bool I2cDevice::readRegister14(uint8_t reg, float& out) const {
|
||||
|
||||
bool I2cDevice::readRegister16(uint8_t reg, uint16_t& out) const {
|
||||
std::uint8_t data[2] = {0};
|
||||
if (masterReadRegister(port, address, reg, data, 2, DEFAULT_TIMEOUT)) {
|
||||
if (i2c_controller_read_register(controller, address, reg, data, 2, DEFAULT_TIMEOUT) == ERROR_NONE) {
|
||||
out = data[0] << 8 | data[1];
|
||||
return true;
|
||||
} else {
|
||||
@ -51,11 +51,11 @@ bool I2cDevice::readRegister16(uint8_t reg, uint16_t& out) const {
|
||||
}
|
||||
|
||||
bool I2cDevice::readRegister8(uint8_t reg, uint8_t& result) const {
|
||||
return masterWriteRead(port, address, ®, 1, &result, 1, DEFAULT_TIMEOUT);
|
||||
return i2c_controller_write_read(controller, address, ®, 1, &result, 1, DEFAULT_TIMEOUT) == ERROR_NONE;
|
||||
}
|
||||
|
||||
bool I2cDevice::writeRegister8(uint8_t reg, uint8_t value) const {
|
||||
return masterWriteRegister(port, address, reg, &value, 1, DEFAULT_TIMEOUT);
|
||||
return i2c_controller_write_register(controller, address, reg, &value, 1, DEFAULT_TIMEOUT) == ERROR_NONE;
|
||||
}
|
||||
|
||||
bool I2cDevice::bitOn(uint8_t reg, uint8_t bitmask) const {
|
||||
|
||||
@ -19,6 +19,9 @@ enum GroveMode {
|
||||
|
||||
/**
|
||||
* @brief API for Grove drivers.
|
||||
*
|
||||
* The grove driver is meant for external interfaces with two wires that can be used as UART, I2C or GPIO as needed.
|
||||
* It can be used with the Grove connector, but also with others such as Stemma QT.
|
||||
*/
|
||||
struct GroveApi {
|
||||
/**
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user