Skip to content

Instantly share code, notes, and snippets.

@imliubo
Created December 3, 2025 04:15
Show Gist options
  • Select an option

  • Save imliubo/e9a10fb86646f3a554e271f44efb1223 to your computer and use it in GitHub Desktop.

Select an option

Save imliubo/e9a10fb86646f3a554e271f44efb1223 to your computer and use it in GitHub Desktop.
The NessoN1 demonstrates how to share the internal wire bus with a BMS (AW32001, BQ27220), IMU (BMI270), Touch (FT6336U), and IO expander (PI4IOEx2).
#define TwoWire TwoWireInternal
#define Wire WireInternal
#define Wire1 WireInternal1
#include "pins_arduino.h"
#include "../../libraries/Wire/src/Wire.h"
#include "../../libraries/Wire/src/Wire.cpp"
static bool wireInitialized = false;
// IO expander datasheet from https://www.diodes.com/datasheet/download/PI4IOE5V6408.pdf
// Battery charger datasheet from https://www.awinic.com/en/productDetail/AW32001ACSR
// battery gauge datasheet from https://www.ti.com/product/BQ27220
static void writeRegister(uint8_t address, uint8_t reg, uint8_t value) {
WireInternal.beginTransmission(address);
WireInternal.write(reg);
WireInternal.write(value);
WireInternal.endTransmission();
}
static uint8_t readRegister(uint8_t address, uint8_t reg) {
WireInternal.beginTransmission(address);
WireInternal.write(reg);
WireInternal.endTransmission(false);
WireInternal.requestFrom(address, 1);
return WireInternal.read();
}
static void writeBitRegister(uint8_t address, uint8_t reg, uint8_t bit, uint8_t value) {
uint8_t val = readRegister(address, reg);
if (value) {
writeRegister(address, reg, val | (1 << bit));
} else {
writeRegister(address, reg, val & ~(1 << bit));
}
}
static bool readBitRegister(uint8_t address, uint8_t reg, uint8_t bit) {
uint8_t val = readRegister(address, reg);
return ((val & (1 << bit)) > 0);
}
void pinMode(ExpanderPin pin, uint8_t mode) {
if (!wireInitialized) {
WireInternal.begin(SDA, SCL);
wireInitialized = true;
// reset all registers to default state
writeRegister(pin.address, 0x1, 0x1);
// set all pins as high as default state
writeRegister(pin.address, 0x9, 0xFF);
// interrupt mask to all pins
writeRegister(pin.address, 0x11, 0xFF);
// all input
writeRegister(pin.address, 0x3, 0);
}
writeBitRegister(pin.address, 0x3, pin.pin, mode == OUTPUT);
if (mode == OUTPUT) {
// remove high impedance
writeBitRegister(pin.address, 0x7, pin.pin, false);
} else if (mode == INPUT_PULLUP) {
// set pull-up resistor
writeBitRegister(pin.address, 0xB, pin.pin, true);
writeBitRegister(pin.address, 0xD, pin.pin, true);
} else if (mode == INPUT_PULLDOWN) {
// disable pull-up resistor
writeBitRegister(pin.address, 0xB, pin.pin, true);
writeBitRegister(pin.address, 0xD, pin.pin, false);
} else if (mode == INPUT) {
// disable pull selector resistor
writeBitRegister(pin.address, 0xB, pin.pin, false);
}
}
void digitalWrite(ExpanderPin pin, uint8_t val) {
if (!wireInitialized) {
WireInternal.begin(SDA, SCL);
wireInitialized = true;
}
writeBitRegister(pin.address, 0x5, pin.pin, val == HIGH);
}
int digitalRead(ExpanderPin pin) {
if (!wireInitialized) {
WireInternal.begin(SDA, SCL);
wireInitialized = true;
}
return readBitRegister(pin.address, 0xF, pin.pin);
}
void NessoBattery::begin(uint16_t current, uint16_t voltage, UnderVoltageLockout uvlo, uint16_t dpm_voltage, uint8_t timeout) {
if (!wireInitialized) {
WireInternal.begin(SDA, SCL);
wireInitialized = true;
}
setChargeCurrent(current);
setChargeVoltage(voltage);
setWatchdogTimer(timeout);
setBatUVLO(uvlo);
setVinDPMVoltage(dpm_voltage);
setHiZ(false);
setChargeEnable(true);
}
void NessoBattery::enableCharge() {
setChargeEnable(true);
}
void NessoBattery::setChargeEnable(bool enable) {
if (!wireInitialized) {
WireInternal.begin(SDA, SCL);
wireInitialized = true;
}
// bit 3 set charge enable
writeBitRegister(AW32001_I2C_ADDR, AW3200_POWER_ON_CFG, 3, !enable);
}
void NessoBattery::setVinDPMVoltage(uint16_t voltage) {
if (!wireInitialized) {
WireInternal.begin(SDA, SCL);
wireInitialized = true;
}
if (voltage < 3880) {
voltage = 3880;
}
if (voltage > 5080) {
voltage = 5080;
}
uint8_t reg_value = readRegister(AW32001_I2C_ADDR, AW3200_INPUT_SRC);
// bits 7-4 set Vin DPM voltage
reg_value &= ~0b01111000;
reg_value |= ((voltage - 3880) / 80) << 4;
writeRegister(AW32001_I2C_ADDR, AW3200_INPUT_SRC, reg_value);
}
void NessoBattery::setIinLimitCurrent(uint16_t current) {
if (!wireInitialized) {
WireInternal.begin(SDA, SCL);
wireInitialized = true;
}
if (current < 50) {
current = 50;
}
if (current > 500) {
current = 500;
}
uint8_t reg_value = readRegister(AW32001_I2C_ADDR, AW3200_INPUT_SRC);
// bits 3-0 set Iin limit current
reg_value &= ~0b00001111;
reg_value |= ((current - 50) / 30) & 0b00001111;
writeRegister(AW32001_I2C_ADDR, AW3200_INPUT_SRC, reg_value);
}
void NessoBattery::setBatUVLO(UnderVoltageLockout uvlo) {
if (!wireInitialized) {
WireInternal.begin(SDA, SCL);
wireInitialized = true;
}
uint8_t reg_value = readRegister(AW32001_I2C_ADDR, AW3200_POWER_ON_CFG);
// bits 2-0 set UVLO
reg_value &= ~0b00000111;
reg_value |= (uvlo & 0b00000111);
writeRegister(AW32001_I2C_ADDR, AW3200_POWER_ON_CFG, reg_value);
}
void NessoBattery::setChargeCurrent(uint16_t current) {
if (!wireInitialized) {
WireInternal.begin(SDA, SCL);
wireInitialized = true;
}
if (current < 8) {
current = 8;
}
if (current > 456) {
current = 456;
}
uint8_t reg_value = readRegister(AW32001_I2C_ADDR, AW3200_CHG_CURRENT);
// bits 5-0 set charge current
reg_value &= ~0b00111111;
reg_value |= ((current - 8) / 8) & 0b00111111;
writeRegister(AW32001_I2C_ADDR, AW3200_CHG_CURRENT, reg_value);
}
void NessoBattery::setDischargeCurrent(uint16_t current) {
if (!wireInitialized) {
WireInternal.begin(SDA, SCL);
wireInitialized = true;
}
if (current < 200) {
current = 200;
}
if (current > 3200) {
current = 3200;
}
uint8_t reg_value = readRegister(AW32001_I2C_ADDR, AW3200_TERM_CURRENT);
// bits 7-4 set discharge current
reg_value &= ~0b11110000;
reg_value |= (((current - 200) / 200) & 0b00001111) << 4;
writeRegister(AW32001_I2C_ADDR, AW3200_TERM_CURRENT, reg_value);
}
void NessoBattery::setChargeVoltage(uint16_t voltage) {
if (!wireInitialized) {
WireInternal.begin(SDA, SCL);
wireInitialized = true;
}
if (voltage < 3600) {
voltage = 3600;
}
if (voltage > 4545) {
voltage = 4545;
}
uint8_t reg_value = readRegister(AW32001_I2C_ADDR, AW3200_CHG_VOLTAGE);
// bits 7-2 set charge voltage
reg_value &= ~0b11111100;
reg_value |= ((voltage - 3600) / 15) << 2;
writeRegister(AW32001_I2C_ADDR, AW3200_CHG_VOLTAGE, reg_value);
}
void NessoBattery::setWatchdogTimer(uint8_t sec) {
if (!wireInitialized) {
WireInternal.begin(SDA, SCL);
wireInitialized = true;
}
uint8_t reg_value = readRegister(AW32001_I2C_ADDR, AW3200_TIMER_WD);
uint8_t bits = 0;
switch (sec) {
case 0:
bits = 0b00; // disable watchdog
break;
case 40: bits = 0b01; break;
case 80: bits = 0b10; break;
case 160: bits = 0b11; break;
default: bits = 0b11; break;
}
// bits 6-5 set watchdog timer
reg_value &= ~(0b11 << 5);
reg_value |= (bits << 5);
writeRegister(AW32001_I2C_ADDR, AW3200_TIMER_WD, reg_value);
}
void NessoBattery::feedWatchdog() {
if (!wireInitialized) {
WireInternal.begin(SDA, SCL);
wireInitialized = true;
}
// bit 6 set feed watchdog
writeBitRegister(AW32001_I2C_ADDR, AW3200_CHG_CURRENT, 6, true);
}
void NessoBattery::setShipMode(bool en) {
if (!wireInitialized) {
WireInternal.begin(SDA, SCL);
wireInitialized = true;
}
// bit 5 set ship mode
writeBitRegister(AW32001_I2C_ADDR, AW3200_MAIN_CTRL, 5, en);
}
NessoBattery::ChargeStatus NessoBattery::getChargeStatus() {
if (!wireInitialized) {
WireInternal.begin(SDA, SCL);
wireInitialized = true;
}
uint8_t status = readRegister(AW32001_I2C_ADDR, AW3200_SYS_STATUS);
// bits 4-3 set charge status
uint8_t charge_status = (status >> 3) & 0b11;
return static_cast<ChargeStatus>(charge_status);
}
void NessoBattery::setHiZ(bool enable) {
if (!wireInitialized) {
WireInternal.begin(SDA, SCL);
wireInitialized = true;
}
// bit 4 set Hi-Z mode
writeBitRegister(AW32001_I2C_ADDR, AW3200_POWER_ON_CFG, 4, enable);
}
float NessoBattery::getVoltage() {
if (!wireInitialized) {
WireInternal.begin(SDA, SCL);
wireInitialized = true;
}
uint16_t voltage = (readRegister(BQ27220_I2C_ADDR, BQ27220_VOLTAGE + 1) << 8) | readRegister(BQ27220_I2C_ADDR, BQ27220_VOLTAGE);
return (float)voltage / 1000.0f;
}
float NessoBattery::getCurrent() {
if (!wireInitialized) {
WireInternal.begin(SDA, SCL);
wireInitialized = true;
}
int16_t current = (readRegister(BQ27220_I2C_ADDR, BQ27220_CURRENT + 1) << 8) | readRegister(BQ27220_I2C_ADDR, BQ27220_CURRENT);
return (float)current / 1000.0f;
}
uint16_t NessoBattery::getChargeLevel() {
if (!wireInitialized) {
WireInternal.begin(SDA, SCL);
wireInitialized = true;
}
uint16_t current_capacity = readRegister(BQ27220_I2C_ADDR, BQ27220_REMAIN_CAPACITY + 1) << 8 | readRegister(BQ27220_I2C_ADDR, BQ27220_REMAIN_CAPACITY);
uint16_t total_capacity = readRegister(BQ27220_I2C_ADDR, BQ27220_FULL_CAPACITY + 1) << 8 | readRegister(BQ27220_I2C_ADDR, BQ27220_FULL_CAPACITY);
return (current_capacity * 100) / total_capacity;
}
int16_t NessoBattery::getAvgPower() {
if (!wireInitialized) {
WireInternal.begin(SDA, SCL);
wireInitialized = true;
}
int16_t avg_power = readRegister(BQ27220_I2C_ADDR, BQ27220_AVG_POWER + 1) << 8 | readRegister(BQ27220_I2C_ADDR, BQ27220_AVG_POWER);
return avg_power;
}
float NessoBattery::getTemperature() {
if (!wireInitialized) {
WireInternal.begin(SDA, SCL);
wireInitialized = true;
}
uint16_t temp = readRegister(BQ27220_I2C_ADDR, BQ27220_TEMPERATURE + 1) << 8 | readRegister(BQ27220_I2C_ADDR, BQ27220_TEMPERATURE);
return ((float)temp / 10.0f) - 273.15f;
}
uint16_t NessoBattery::getCycleCount() {
if (!wireInitialized) {
WireInternal.begin(SDA, SCL);
wireInitialized = true;
}
uint16_t cycle_count = readRegister(BQ27220_I2C_ADDR, BQ27220_CYCLE_COUNT + 1) << 8 | readRegister(BQ27220_I2C_ADDR, BQ27220_CYCLE_COUNT);
return cycle_count;
}
ExpanderPin LORA_LNA_ENABLE(5);
ExpanderPin LORA_ANTENNA_SWITCH(6);
ExpanderPin LORA_ENABLE(7);
ExpanderPin KEY1(0);
ExpanderPin KEY2(1);
ExpanderPin POWEROFF((1 << 8) | 0);
ExpanderPin LCD_RESET((1 << 8) | 1);
ExpanderPin GROVE_POWER_EN((1 << 8) | 2);
ExpanderPin VIN_DETECT((1 << 8) | 5);
ExpanderPin LCD_BACKLIGHT((1 << 8) | 6);
ExpanderPin LED_BUILTIN((1 << 8) | 7);
TwoWire* getInternalWire() {
if (!wireInitialized) {
WireInternal.begin(SDA, SCL);
wireInitialized = true;
}
return &WireInternal;
}
#include <Arduino.h>
#include <Wire.h>
#include <M5GFX.h>
#include <lgfx/v1/panel/Panel_ST7789.hpp>
#include "Arduino_BMI270_BMM150.h"
#define DEBUG_SERIAL Serial
// #define DEBUG_SERIAL Serial1
class NessoN1_Lcd : public lgfx::LGFX_Device {
lgfx::Panel_ST7789 _panel_instance;
lgfx::Bus_SPI _bus_instance;
public:
NessoN1_Lcd(void) {
{
auto cfg = _bus_instance.config();
cfg.pin_mosi = 21;
cfg.pin_miso = 22;
cfg.pin_sclk = 20;
cfg.pin_dc = 16;
cfg.freq_write = 40000000;
_bus_instance.config(cfg);
_panel_instance.setBus(&_bus_instance);
}
{
auto cfg = _panel_instance.config();
cfg.invert = true;
cfg.pin_cs = 17;
cfg.pin_rst = -1;
cfg.pin_busy = -1;
cfg.panel_width = 135;
cfg.panel_height = 240;
cfg.offset_x = 52;
cfg.offset_y = 40;
_panel_instance.config(cfg);
}
setPanel(&_panel_instance);
}
};
class NessoN1_Touch {
private:
TwoWire *_wire;
uint8_t _addr;
bool _inited;
// FT6x36 register definitions
static const uint8_t FT6X36_ADDR = 0x38;
static const uint8_t FT6X36_TD_STAT_REG = 0x02;
static const uint8_t FT6X36_P1_XH_REG = 0x03;
uint8_t readRegister(uint8_t reg) {
_wire->beginTransmission(_addr);
_wire->write(reg);
_wire->endTransmission();
_wire->requestFrom(_addr, (uint8_t)1);
return _wire->read();
}
void readRegisters(uint8_t reg, uint8_t *buf, uint8_t len) {
_wire->beginTransmission(_addr);
_wire->write(reg);
_wire->endTransmission();
_wire->requestFrom(_addr, len);
for (uint8_t i = 0; i < len; i++) {
buf[i] = _wire->read();
}
}
public:
NessoN1_Touch(TwoWire &wire = Wire)
: _wire(&wire), _addr(FT6X36_ADDR), _inited(false) {}
bool begin() {
if (_inited) return true;
_wire->beginTransmission(_addr);
if (_wire->endTransmission() == 0) {
_inited = true;
return true;
}
return false;
}
// Check if touch is detected
bool isTouched() {
if (!_inited) return false;
uint8_t touchPoints = readRegister(FT6X36_TD_STAT_REG) & 0x0F;
return (touchPoints == 1); // Only handle single touch
}
// Read touch coordinates
bool read(int16_t &x, int16_t &y) {
if (!_inited) return false;
uint8_t data[4];
readRegisters(FT6X36_P1_XH_REG, data, 4);
uint8_t touchPoints = readRegister(FT6X36_TD_STAT_REG) & 0x0F;
if (touchPoints != 1) {
return false;
}
x = ((data[0] & 0x0F) << 8) | data[1];
y = ((data[2] & 0x0F) << 8) | data[3];
return true;
}
};
class MyBoschSensor : public BoschSensorClass {
public:
MyBoschSensor(TwoWire &wire = Wire)
: BoschSensorClass(wire){};
protected:
virtual int8_t configure_sensor(struct bmi2_dev *dev) {
int8_t rslt;
uint8_t sens_list[2] = { BMI2_ACCEL, BMI2_GYRO };
struct bmi2_int_pin_config int_pin_cfg;
int_pin_cfg.pin_type = BMI2_INT1;
int_pin_cfg.int_latch = BMI2_INT_NON_LATCH;
int_pin_cfg.pin_cfg[0].lvl = BMI2_INT_ACTIVE_LOW;
int_pin_cfg.pin_cfg[0].od = BMI2_INT_OPEN_DRAIN;
int_pin_cfg.pin_cfg[0].output_en = BMI2_INT_OUTPUT_ENABLE;
int_pin_cfg.pin_cfg[0].input_en = BMI2_INT_INPUT_DISABLE;
struct bmi2_sens_config sens_cfg[2];
sens_cfg[0].type = BMI2_ACCEL;
sens_cfg[0].cfg.acc.bwp = BMI2_ACC_OSR2_AVG2;
sens_cfg[0].cfg.acc.odr = BMI2_ACC_ODR_25HZ;
sens_cfg[0].cfg.acc.filter_perf = BMI2_PERF_OPT_MODE;
sens_cfg[0].cfg.acc.range = BMI2_ACC_RANGE_4G;
sens_cfg[1].type = BMI2_GYRO;
sens_cfg[1].cfg.gyr.filter_perf = BMI2_PERF_OPT_MODE;
sens_cfg[1].cfg.gyr.bwp = BMI2_GYR_OSR2_MODE;
sens_cfg[1].cfg.gyr.odr = BMI2_GYR_ODR_25HZ;
sens_cfg[1].cfg.gyr.range = BMI2_GYR_RANGE_2000;
sens_cfg[1].cfg.gyr.ois_range = BMI2_GYR_OIS_2000;
rslt = bmi2_sensor_disable(sens_list, 2, dev);
if (rslt != BMI2_OK)
return rslt;
rslt = bmi2_set_int_pin_config(&int_pin_cfg, dev);
if (rslt != BMI2_OK)
return rslt;
rslt = bmi2_set_sensor_config(sens_cfg, 2, dev);
if (rslt != BMI2_OK)
return rslt;
rslt = bmi2_map_data_int(BMI2_DRDY_INT, BMI2_INT1, dev);
if (rslt != BMI2_OK)
return rslt;
rslt = bmi2_sensor_enable(sens_list, 2, dev);
if (rslt != BMI2_OK)
return rslt;
return rslt;
}
};
// The NessoBattery object is available by default
NessoBattery battery;
NessoN1_Lcd lcd;
NessoN1_Touch touch(*getInternalWire());
MyBoschSensor myIMU(*getInternalWire()); // We use internal Wire Bus, need change the board variant file.
void setup() {
// DEBUG_SERIAL.begin(115200, SERIAL_8N1, 4, 5); // Use Grove PortA as debug port
DEBUG_SERIAL.print("hello world\r\n");
// Battery
battery.begin();
// Ext GPIO
pinMode(LED_BUILTIN, OUTPUT);
pinMode(LCD_BACKLIGHT, OUTPUT);
pinMode(LCD_RESET, OUTPUT);
pinMode(KEY1, INPUT_PULLUP);
pinMode(KEY2, INPUT_PULLUP);
digitalWrite(LCD_BACKLIGHT, HIGH);
digitalWrite(LCD_RESET, LOW);
delay(100);
digitalWrite(LCD_RESET, HIGH);
// IMU
myIMU.debug(DEBUG_SERIAL);
myIMU.begin(BOSCH_ACCELEROMETER_ONLY);
myIMU.oneShotMode();
// LCD
lcd.begin();
lcd.fillScreen(TFT_BLUE);
lcd.setTextSize(2);
lcd.setTextColor(TFT_WHITE, TFT_BLUE);
// Touch
if (touch.begin()) {
DEBUG_SERIAL.println("Touch initialized");
} else {
DEBUG_SERIAL.println("Touch init failed");
}
}
uint32_t count = 0;
uint64_t bat_check_time = 0;
void loop() {
if ((millis() - bat_check_time) > 3000) {
bat_check_time = millis();
DEBUG_SERIAL.printf("\r\n========%ld========\r\n", count++);
float voltage = battery.getVoltage();
DEBUG_SERIAL.print("Voltage: ");
DEBUG_SERIAL.print(voltage);
DEBUG_SERIAL.println(" V");
float current = battery.getCurrent();
DEBUG_SERIAL.print("Current: ");
DEBUG_SERIAL.print(current);
DEBUG_SERIAL.println(" A");
float temp = battery.getTemperature();
DEBUG_SERIAL.print("Temp: ");
DEBUG_SERIAL.print(temp);
DEBUG_SERIAL.println(" C");
float power = battery.getAvgPower();
DEBUG_SERIAL.print("power: ");
DEBUG_SERIAL.print(power);
DEBUG_SERIAL.println(" mW");
uint16_t count = battery.getCycleCount();
DEBUG_SERIAL.print("count: ");
DEBUG_SERIAL.print(count);
DEBUG_SERIAL.println(" times");
float x, y, z;
if (myIMU.accelerationAvailable()) {
myIMU.readAcceleration(x, y, z);
DEBUG_SERIAL.print("accel: \t");
DEBUG_SERIAL.print(x);
DEBUG_SERIAL.print('\t');
DEBUG_SERIAL.print(y);
DEBUG_SERIAL.print('\t');
DEBUG_SERIAL.print(z);
DEBUG_SERIAL.println();
}
if (myIMU.gyroscopeAvailable()) {
myIMU.readGyroscope(x, y, z);
DEBUG_SERIAL.print("gyro: \t");
DEBUG_SERIAL.print(x);
DEBUG_SERIAL.print('\t');
DEBUG_SERIAL.print(y);
DEBUG_SERIAL.print('\t');
DEBUG_SERIAL.print(z);
DEBUG_SERIAL.println();
}
battery.feedWatchdog();
}
// Touch detection and display
int16_t touch_x, touch_y;
if (touch.read(touch_x, touch_y)) {
lcd.fillCircle(touch_x, touch_y, 5, random(0, 0xFFFF));
}
// Clear screen on key press
if (digitalRead(KEY1) == LOW) {
lcd.fillScreen(TFT_BLUE);
}
// Change screen to random color on key press
if (digitalRead(KEY2) == LOW) {
lcd.fillScreen(random(0, 0xFFFF));
}
delay(10);
}
#ifndef Pins_Arduino_h
#define Pins_Arduino_h
#include <stdint.h>
#include "soc/soc_caps.h"
#define USB_VID 0x303A
#define USB_PID 0x1001
#define USB_MANUFACTURER "Arduino"
#define USB_PRODUCT "Nesso N1"
#define USB_SERIAL ""
static const uint8_t TX = -1;
static const uint8_t RX = -1;
static const uint8_t SDA = 10;
static const uint8_t SCL = 8;
static const uint8_t MOSI = 21;
static const uint8_t MISO = 22;
static const uint8_t SCK = 20;
static const uint8_t SS = 23;
static const uint8_t D1 = 7;
static const uint8_t D2 = 2;
static const uint8_t D3 = 6;
static const uint8_t IR_TX_PIN = 9;
static const uint8_t BEEP_PIN = 11;
static const uint8_t GROVE_IO_0 = 5;
static const uint8_t GROVE_IO_1 = 4;
static const uint8_t LORA_IRQ = 15;
static const uint8_t LORA_CS = 23;
static const uint8_t LORA_BUSY = 19;
static const uint8_t SYS_IRQ = 3;
static const uint8_t LCD_CS = 17;
static const uint8_t LCD_RS = 16;
#if !defined(MAIN_ESP32_HAL_GPIO_H_) && defined(__cplusplus)
#include "../../libraries/Wire/src/Wire.h"
/* address: 0x43(C6 LoRa Module), 0x44(N1 Board) */
class ExpanderPin {
public:
ExpanderPin(uint16_t _pin) : pin(_pin & 0xFF), address(_pin & 0x100 ? 0x44 : 0x43){};
uint8_t pin;
uint8_t address;
};
class NessoBattery {
public:
static constexpr uint8_t AW32001_I2C_ADDR = 0x49;
static constexpr uint8_t BQ27220_I2C_ADDR = 0x55;
enum AW32001Reg : uint8_t {
AW3200_INPUT_SRC = 0x00,
AW3200_POWER_ON_CFG = 0x01,
AW3200_CHG_CURRENT = 0x02,
AW3200_TERM_CURRENT = 0x03,
AW3200_CHG_VOLTAGE = 0x04,
AW3200_TIMER_WD = 0x05,
AW3200_MAIN_CTRL = 0x06,
AW3200_SYS_CTRL = 0x07,
AW3200_SYS_STATUS = 0x08,
AW3200_FAULT_STATUS = 0x09,
AW3200_CHIP_ID = 0x0A,
};
enum BQ27220Reg : uint8_t {
BQ27220_VOLTAGE = 0x08,
BQ27220_CURRENT = 0x0C,
BQ27220_REMAIN_CAPACITY = 0x10,
BQ27220_FULL_CAPACITY = 0x12,
BQ27220_AVG_POWER = 0x24,
BQ27220_TEMPERATURE = 0x28,
BQ27220_CYCLE_COUNT = 0x2A,
};
enum ChargeStatus {
NOT_CHARGING = 0,
PRE_CHARGE = 1,
CHARGING = 2,
FULL_CHARGE = 3,
};
enum UnderVoltageLockout {
UVLO_2430mV = 0,
UVLO_2490mV = 1,
UVLO_2580mV = 2,
UVLO_2670mV = 3,
UVLO_2760mV = 4,
UVLO_2850mV = 5,
UVLO_2940mV = 6,
UVLO_3030mV = 7,
};
NessoBattery(){};
void begin(
uint16_t current = 256, uint16_t voltage = 4200, UnderVoltageLockout uvlo = UVLO_2580mV, uint16_t dpm_voltage = 4520, uint8_t timeout = 0
); // default: charge current 256mA, battery 4200mV, uvlo 2580mV, DMP 4520mV, disable watchdog
// AW32001 functions
void enableCharge(); // enable charging
void setChargeEnable(bool enable); // charge control
void setVinDPMVoltage(uint16_t voltage); // set input voltage limit, 3880mV ~ 5080mV(step 80mV, default 4520mV)
void setIinLimitCurrent(uint16_t current); // set input current limit, 50mA ~ 500mA(step 30mA, default 500mA)
void setBatUVLO(UnderVoltageLockout uvlo); // set battery under voltage lockout(2430mV, 2490mV, 2580mV, 2670mV, 2760mV, 2850mV, 2940mV, 3030mV)
void setChargeCurrent(uint16_t current); // set charging current, 8mA ~ 456mA(step 8mA, default 128mA)
void setDischargeCurrent(uint16_t current); // set discharging current, 200mA ~ 3200mA(step 200mA, default 2000mA)
void setChargeVoltage(uint16_t voltage); // set charging voltage, 3600mV ~ 4545mV(step 15mV, default 4200mV)
void setWatchdogTimer(uint8_t sec); // set charge watchdog timeout(0s, 40s, 80s, 160s, default 160s, 0 to disable)
void feedWatchdog(); // feed watchdog timer
void setShipMode(bool en); // set ship mode
ChargeStatus getChargeStatus(); // get charge status
void setHiZ(bool enable); // set Hi-Z mode, true: USB -x-> SYS, false: USB -> SYS
// BQ27220 functions
float getVoltage(); // get battery voltage in Volts
float getCurrent(); // get battery current in Amperes
uint16_t getChargeLevel(); // get battery charge level in percents
int16_t getAvgPower(); // get average power in mWatts, can be negative
float getTemperature(); // get battery temperature in Celsius
uint16_t getCycleCount(); // get battery cycle count
};
extern ExpanderPin LORA_LNA_ENABLE;
extern ExpanderPin LORA_ANTENNA_SWITCH;
extern ExpanderPin LORA_ENABLE;
extern ExpanderPin POWEROFF;
extern ExpanderPin GROVE_POWER_EN;
extern ExpanderPin VIN_DETECT;
extern ExpanderPin LCD_RESET;
extern ExpanderPin LCD_BACKLIGHT;
extern ExpanderPin LED_BUILTIN;
extern ExpanderPin KEY1;
extern ExpanderPin KEY2;
extern TwoWire* getInternalWire();
void pinMode(ExpanderPin pin, uint8_t mode);
void digitalWrite(ExpanderPin pin, uint8_t val);
int digitalRead(ExpanderPin pin);
#endif
#endif /* Pins_Arduino_h */
@ubidefeo
Copy link

ubidefeo commented Dec 3, 2025

@imliubo
here's my demo sketch with the changes required to work with NessoN1_Lcd
tested and working :)

it's a 2 files sketch, the main .ino and a .h (to keep the user code cleaner

extras.h

#include <M5GFX.h>
#include <lgfx/v1/panel/Panel_ST7789.hpp>


class NessoN1_Lcd : public lgfx::LGFX_Device {
  lgfx::Panel_ST7789 _panel_instance;
  lgfx::Bus_SPI _bus_instance;

public:
  NessoN1_Lcd(void) {
    {
      auto cfg = _bus_instance.config();

      cfg.pin_mosi = 21;
      cfg.pin_miso = 22;
      cfg.pin_sclk = 20;
      cfg.pin_dc = 16;
      cfg.freq_write = 40000000;

      _bus_instance.config(cfg);
      _panel_instance.setBus(&_bus_instance);
    }
    {
      auto cfg = _panel_instance.config();

      cfg.invert = true;
      cfg.pin_cs = 17;
      cfg.pin_rst = -1;
      cfg.pin_busy = -1;
      cfg.panel_width = 135;
      cfg.panel_height = 240;
      cfg.offset_x = 52;
      cfg.offset_y = 40;

      _panel_instance.config(cfg);
    }

    setPanel(&_panel_instance);
  }
};

class NessoN1_Touch {
private:
  TwoWire *_wire;
  uint8_t _addr;
  bool _inited;

  // FT6x36 register definitions
  static const uint8_t FT6X36_ADDR = 0x38;
  static const uint8_t FT6X36_TD_STAT_REG = 0x02;
  static const uint8_t FT6X36_P1_XH_REG = 0x03;

  uint8_t readRegister(uint8_t reg) {
    _wire->beginTransmission(_addr);
    _wire->write(reg);
    _wire->endTransmission();
    _wire->requestFrom(_addr, (uint8_t)1);
    return _wire->read();
  }

  void readRegisters(uint8_t reg, uint8_t *buf, uint8_t len) {
    _wire->beginTransmission(_addr);
    _wire->write(reg);
    _wire->endTransmission();
    _wire->requestFrom(_addr, len);
    for (uint8_t i = 0; i < len; i++) {
      buf[i] = _wire->read();
    }
  }

public:
  NessoN1_Touch(TwoWire &wire = Wire)
    : _wire(&wire), _addr(FT6X36_ADDR), _inited(false) {}

  bool begin() {
    if (_inited) return true;
    
    _wire->beginTransmission(_addr);
    if (_wire->endTransmission() == 0) {
      _inited = true;
      return true;
    }
    return false;
  }

  // Check if touch is detected
  bool isTouched() {
    if (!_inited) return false;
    uint8_t touchPoints = readRegister(FT6X36_TD_STAT_REG) & 0x0F;
    return (touchPoints == 1);  // Only handle single touch
  }

  // Read touch coordinates
  bool read(int16_t &x, int16_t &y) {
    if (!_inited) return false;
    
    uint8_t data[4];
    readRegisters(FT6X36_P1_XH_REG, data, 4);
    
    uint8_t touchPoints = readRegister(FT6X36_TD_STAT_REG) & 0x0F;
    if (touchPoints != 1) {
      return false;
    }
    
    x = ((data[0] & 0x0F) << 8) | data[1];
    y = ((data[2] & 0x0F) << 8) | data[3];
    
    return true;
  }
};

nesso_n1_battery.ino

#include "extras.h"

NessoBattery nb;
// M5GFX display;
NessoN1_Lcd display;

const int DISPLAY_WIDTH = 240;
const int DISPLAY_HEIGHT = 135;
const uint16_t COLOR_TEAL = 0x0410;
const uint16_t COLOR_BLACK = 0x0000;
const uint16_t COLOR_GREEN = 0x1e85;
const uint16_t COLOR_ORANGE = 0xed03;
const uint16_t COLOR_RED = 0xe841;
const int ANIMATION_DELAY = 30;
const int COLS = 20;
const int ROWS = 1;
const int REGION_WIDTH = 12;
const int REGION_HEIGHT = 135;
LGFX_Sprite batterySprite(&display);
LGFX_Sprite uptimeSprite(&display);

float batteryVoltage = 0.0;
int counter = 0;
char uptimeString[26];
bool ledStatus = false;
unsigned long lastLEDflip = 0;
int progressEdge = 240;
bool progressExpanding = true;

void setup() {
  /*
    a .begin() in the NessoBattery object will only be available from core 3.3.5
  */
  // pinMode(LED_BUILTIN, OUTPUT);
  nb.begin();
  Serial.begin(115200);
  
  delay(3000);
  Serial.println("Display begin()");
  display.begin();
  delay(3000);
  Serial.println("Battery enableCharge()");
  nb.enableCharge();
  delay(3000);
  Serial.println("moving on");
  display.setRotation(1);
  display.setEpdMode(epd_mode_t::epd_fastest);
  batterySprite.createSprite(240, 81);
  display.fillScreen(TFT_WHITE);
  display.setTextColor(COLOR_TEAL);
  display.setTextSize(5);
  display.drawString("Nesso N1", 6, 11);
  Serial.println();
  Serial.println();
  Serial.println("***************************************");
  Serial.println("***************  START  ***************");
  Serial.println("***************************************");
  Serial.println();
  Serial.println();
  delay(5000);
  lastLEDflip = millis();
  
}

void loop() {
  unsigned long msNow = millis();
  float bv = nb.getVoltage();
  float cl = nb.getChargeLevel();
  batteryVoltage = bv;
  showBatteryState();

  char batteryStatusTicker[16];
  sprintf(batteryStatusTicker, "%4.2f %6.2f%%", bv, cl);
  
  if(msNow - lastLEDflip > 1000){
    ledStatus = !ledStatus;
    Serial.println(ledStatus);
    // digitalWrite(LED_BUILTIN, ledStatus);
    lastLEDflip = msNow;

    Serial.print(bv);
    Serial.print(" ");
    Serial.print(cl);
    Serial.println("%");
    sprintf(uptimeString, "uptime:\n%012d\n", millis() / 1000);
    Serial.println(uptimeString);
  }
}

void showBatteryState() {
  int offsetY = 18;
  batterySprite.fillSprite(TFT_WHITE);
  batterySprite.setColor(COLOR_ORANGE);
  if(progressExpanding){
    batterySprite.fillRect(progressEdge, 0, 240, 8);
  }else{
    batterySprite.fillRect(0, 0, progressEdge, 8);
  }

  progressEdge -= 1;
  if(progressEdge <= 0){
    progressEdge = 240;
    progressExpanding = !progressExpanding;
  }
  batterySprite.setTextSize(3);
  batterySprite.setTextColor(COLOR_BLACK);
  batterySprite.drawString("Battery:", 6, offsetY);
  uint16_t textColor = 0x0000;
  if(batteryVoltage > 3.7){
    textColor = COLOR_GREEN;
  }else if(batteryVoltage <= 3.7 && batteryVoltage >= 3.3){
    textColor = COLOR_ORANGE;
  }else{
    textColor = COLOR_RED;
  }
  char batteryString[6];
  sprintf(batteryString, "%4.2f", batteryVoltage);
  batterySprite.setTextColor(textColor);
  batterySprite.drawString(batteryString, 165, offsetY);
  batterySprite.setTextColor(COLOR_BLACK);
  batterySprite.setTextSize(2);
  
  batterySprite.setTextColor(COLOR_TEAL);
  batterySprite.drawString(uptimeString, 6 , offsetY + 38);
  batterySprite.pushSprite(0, 54);
  // 
}

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment