Skip to content

Commit

Permalink
Feature: add support for a third Victron MPPT
Browse files Browse the repository at this point in the history
only on ESP32-S3-USB. this fiddles with the available hardware UARTs to
make it possible to use a third Victron MPPT. if three MPPTs are defined
int the pin mapping, you will not be able to use the SmartShunt and JK
BMS battery interfaces.

note that using a second MPPT will also conflict with the SDM power
meter, and that conflict is not detected, yet.
  • Loading branch information
schlimmchen committed Jun 2, 2024
1 parent 90aafe2 commit 5a1c3af
Show file tree
Hide file tree
Showing 20 changed files with 111 additions and 59 deletions.
2 changes: 1 addition & 1 deletion include/Battery.h
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ class BatteryProvider {
virtual void deinit() = 0;
virtual void loop() = 0;
virtual std::shared_ptr<BatteryStats> getStats() const = 0;
virtual bool usesHwPort2() const { return false; }
virtual int usedHwUart() const { return -1; } // -1 => no HW UART used
};

class BatteryClass {
Expand Down
6 changes: 3 additions & 3 deletions include/JkBmsController.h
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,8 @@ class DataPointContainer;

namespace JkBms {

uint8_t constexpr HwSerialPort = ((ARDUINO_USB_CDC_ON_BOOT != 1)?2:0);

class Controller : public BatteryProvider {
public:
Controller() = default;
Expand All @@ -19,9 +21,7 @@ class Controller : public BatteryProvider {
void deinit() final;
void loop() final;
std::shared_ptr<BatteryStats> getStats() const final { return _stats; }
bool usesHwPort2() const final {
return ARDUINO_USB_CDC_ON_BOOT != 1;
}
int usedHwUart() const final { return HwSerialPort; }

private:
enum class Status : unsigned {
Expand Down
2 changes: 2 additions & 0 deletions include/PinMapping.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,8 @@ struct PinMapping_t {
int8_t victron_rx;
int8_t victron_tx2;
int8_t victron_rx2;
int8_t victron_tx3;
int8_t victron_rx3;
int8_t battery_rx;
int8_t battery_rxen;
int8_t battery_tx;
Expand Down
10 changes: 6 additions & 4 deletions include/SerialPortManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,14 +5,16 @@

class SerialPortManagerClass {
public:
bool allocateMpptPort(int port);
bool allocateBatteryPort(int port);
void init();
bool allocateMpptPort(uint8_t port);
bool allocateBatteryPort(uint8_t port);
void invalidateBatteryPort();
void invalidateMpptPorts();

private:
enum Owner {
BATTERY,
enum class Owner {
Console,
Battery,
MPPT
};

Expand Down
3 changes: 2 additions & 1 deletion include/VictronMppt.h
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,8 @@ class VictronMpptClass {
using controller_t = std::unique_ptr<VeDirectMpptController>;
std::vector<controller_t> _controllers;

bool initController(int8_t rx, int8_t tx, bool logging, int hwSerialPort);
bool initController(int8_t rx, int8_t tx, bool logging,
uint8_t instance, uint8_t hwSerialPort);
};

extern VictronMpptClass VictronMppt;
5 changes: 2 additions & 3 deletions include/VictronSmartShunt.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,11 +9,10 @@ class VictronSmartShunt : public BatteryProvider {
void deinit() final { }
void loop() final;
std::shared_ptr<BatteryStats> getStats() const final { return _stats; }
bool usesHwPort2() const final {
return ARDUINO_USB_CDC_ON_BOOT != 1;
}
int usedHwUart() const final { return _hwSerialPort; }

private:
static uint8_t constexpr _hwSerialPort = ((ARDUINO_USB_CDC_ON_BOOT != 1)?2:0);
uint32_t _lastUpdate = 0;
std::shared_ptr<VictronSmartShuntStats> _stats =
std::make_shared<VictronSmartShuntStats>();
Expand Down
3 changes: 2 additions & 1 deletion lib/VeDirectFrameHandler/VeDirectFrameHandler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,8 @@ VeDirectFrameHandler<T>::VeDirectFrameHandler() :
}

template<typename T>
void VeDirectFrameHandler<T>::init(char const* who, int8_t rx, int8_t tx, Print* msgOut, bool verboseLogging, uint16_t hwSerialPort)
void VeDirectFrameHandler<T>::init(char const* who, int8_t rx, int8_t tx,
Print* msgOut, bool verboseLogging, uint8_t hwSerialPort)
{
_vedirectSerial = std::make_unique<HardwareSerial>(hwSerialPort);
_vedirectSerial->end(); // make sure the UART will be re-initialized
Expand Down
3 changes: 2 additions & 1 deletion lib/VeDirectFrameHandler/VeDirectFrameHandler.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,8 @@ class VeDirectFrameHandler {

protected:
VeDirectFrameHandler();
void init(char const* who, int8_t rx, int8_t tx, Print* msgOut, bool verboseLogging, uint16_t hwSerialPort);
void init(char const* who, int8_t rx, int8_t tx, Print* msgOut,
bool verboseLogging, uint8_t hwSerialPort);
virtual bool hexDataHandler(VeDirectHexData const &data) { return false; } // handles the disassembeled hex response

bool _verboseLogging;
Expand Down
6 changes: 4 additions & 2 deletions lib/VeDirectFrameHandler/VeDirectMpptController.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,11 @@

//#define PROCESS_NETWORK_STATE

void VeDirectMpptController::init(int8_t rx, int8_t tx, Print* msgOut, bool verboseLogging, uint16_t hwSerialPort)
void VeDirectMpptController::init(int8_t rx, int8_t tx, Print* msgOut,
bool verboseLogging, uint8_t hwSerialPort)
{
VeDirectFrameHandler::init("MPPT", rx, tx, msgOut, verboseLogging, hwSerialPort);
VeDirectFrameHandler::init("MPPT", rx, tx, msgOut,
verboseLogging, hwSerialPort);
}

bool VeDirectMpptController::processTextDataDerived(std::string const& name, std::string const& value)
Expand Down
3 changes: 2 additions & 1 deletion lib/VeDirectFrameHandler/VeDirectMpptController.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,8 @@ class VeDirectMpptController : public VeDirectFrameHandler<veMpptStruct> {
public:
VeDirectMpptController() = default;

void init(int8_t rx, int8_t tx, Print* msgOut, bool verboseLogging, uint16_t hwSerialPort);
void init(int8_t rx, int8_t tx, Print* msgOut,
bool verboseLogging, uint8_t hwSerialPort);

using data_t = veMpptStruct;

Expand Down
7 changes: 4 additions & 3 deletions lib/VeDirectFrameHandler/VeDirectShuntController.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,10 +3,11 @@

VeDirectShuntController VeDirectShunt;

void VeDirectShuntController::init(int8_t rx, int8_t tx, Print* msgOut, bool verboseLogging)
void VeDirectShuntController::init(int8_t rx, int8_t tx, Print* msgOut,
bool verboseLogging, uint8_t hwSerialPort)
{
VeDirectFrameHandler::init("SmartShunt", rx, tx, msgOut, verboseLogging,
((ARDUINO_USB_CDC_ON_BOOT != 1)?2:0));
VeDirectFrameHandler::init("SmartShunt", rx, tx, msgOut,
verboseLogging, hwSerialPort);
}

bool VeDirectShuntController::processTextDataDerived(std::string const& name, std::string const& value)
Expand Down
3 changes: 2 additions & 1 deletion lib/VeDirectFrameHandler/VeDirectShuntController.h
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,8 @@ class VeDirectShuntController : public VeDirectFrameHandler<veShuntStruct> {
public:
VeDirectShuntController() = default;

void init(int8_t rx, int8_t tx, Print* msgOut, bool verboseLogging);
void init(int8_t rx, int8_t tx, Print* msgOut,
bool verboseLogging, uint8_t hwSerialPort);

using data_t = veShuntStruct;

Expand Down
14 changes: 7 additions & 7 deletions src/Battery.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,16 +60,16 @@ void BatteryClass::updateSettings()
_upProvider = std::make_unique<VictronSmartShunt>();
break;
default:
MessageOutput.printf("Unknown battery provider: %d\r\n", config.Battery.Provider);
MessageOutput.printf("[Battery] Unknown provider: %d\r\n", config.Battery.Provider);
return;
}

if(_upProvider->usesHwPort2()) {
if (!SerialPortManager.allocateBatteryPort(2)) {
MessageOutput.printf("[Battery] Serial port %d already in use. Initialization aborted!\r\n", 2);
_upProvider = nullptr;
return;
}
// port is -1 if provider is neither JK BMS nor SmartShunt. otherwise, port
// is 2, unless running on ESP32-S3 with USB CDC, then port is 0.
int port = _upProvider->usedHwUart();
if (port >= 0 && !SerialPortManager.allocateBatteryPort(port)) {
_upProvider = nullptr;
return;
}

if (!_upProvider->init(verboseLogging)) {
Expand Down
6 changes: 3 additions & 3 deletions src/JkBmsController.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,8 @@
#include "JkBmsController.h"
#include <frozen/map.h>

namespace JkBms {

//#define JKBMS_DUMMY_SERIAL

#ifdef JKBMS_DUMMY_SERIAL
Expand Down Expand Up @@ -198,11 +200,9 @@ class DummySerial {
};
DummySerial HwSerial;
#else
HardwareSerial HwSerial((ARDUINO_USB_CDC_ON_BOOT != 1)?2:0);
HardwareSerial HwSerial(HwSerialPort);
#endif

namespace JkBms {

bool Controller::init(bool verboseLogging)
{
_verboseLogging = verboseLogging;
Expand Down
17 changes: 15 additions & 2 deletions src/PinMapping.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,6 +100,14 @@
#define VICTRON_PIN_RX2 -1
#endif

#ifndef VICTRON_PIN_TX3
#define VICTRON_PIN_TX3 -1
#endif

#ifndef VICTRON_PIN_RX3
#define VICTRON_PIN_RX3 -1
#endif

#ifndef BATTERY_PIN_RX
#define BATTERY_PIN_RX -1
#endif
Expand Down Expand Up @@ -207,8 +215,11 @@ PinMappingClass::PinMappingClass()
_pinMapping.victron_rx = VICTRON_PIN_RX;
_pinMapping.victron_tx = VICTRON_PIN_TX;

_pinMapping.victron_rx2 = VICTRON_PIN_RX;
_pinMapping.victron_tx2 = VICTRON_PIN_TX;
_pinMapping.victron_rx2 = VICTRON_PIN_RX2;
_pinMapping.victron_tx2 = VICTRON_PIN_TX2;

_pinMapping.victron_rx3 = VICTRON_PIN_RX3;
_pinMapping.victron_tx3 = VICTRON_PIN_TX3;

_pinMapping.battery_rx = BATTERY_PIN_RX;
_pinMapping.battery_rxen = BATTERY_PIN_RXEN;
Expand Down Expand Up @@ -292,6 +303,8 @@ bool PinMappingClass::init(const String& deviceMapping)
_pinMapping.victron_tx = doc[i]["victron"]["tx"] | VICTRON_PIN_TX;
_pinMapping.victron_rx2 = doc[i]["victron"]["rx2"] | VICTRON_PIN_RX2;
_pinMapping.victron_tx2 = doc[i]["victron"]["tx2"] | VICTRON_PIN_TX2;
_pinMapping.victron_rx3 = doc[i]["victron"]["rx3"] | VICTRON_PIN_RX3;
_pinMapping.victron_tx3 = doc[i]["victron"]["tx3"] | VICTRON_PIN_TX3;

_pinMapping.battery_rx = doc[i]["battery"]["rx"] | BATTERY_PIN_RX;
_pinMapping.battery_rxen = doc[i]["battery"]["rxen"] | BATTERY_PIN_RXEN;
Expand Down
40 changes: 30 additions & 10 deletions src/SerialPortManager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,29 +6,47 @@

SerialPortManagerClass SerialPortManager;

bool SerialPortManagerClass::allocateBatteryPort(int port)
void SerialPortManagerClass::init()
{
return allocatePort(port, Owner::BATTERY);
if (ARDUINO_USB_CDC_ON_BOOT != 1) {
allocatePort(0, Owner::Console);
}
}

bool SerialPortManagerClass::allocateBatteryPort(uint8_t port)
{
return allocatePort(port, Owner::Battery);
}

bool SerialPortManagerClass::allocateMpptPort(int port)
bool SerialPortManagerClass::allocateMpptPort(uint8_t port)
{
return allocatePort(port, Owner::MPPT);
}

bool SerialPortManagerClass::allocatePort(uint8_t port, Owner owner)
{
if (port >= MAX_CONTROLLERS) {
MessageOutput.printf("[SerialPortManager] Invalid serial port = %d \r\n", port);
MessageOutput.printf("[SerialPortManager] Invalid serial port: %d\r\n", port);
return false;
}

auto res = allocatedPorts.insert({port, owner});

if (!res.second) {
MessageOutput.printf("[SerialPortManager] Cannot assign HW UART "
"port %d to %s: already in use by %s\r\n",
port, print(owner), print(res.first->second));
return false;
}

return allocatedPorts.insert({port, owner}).second;
MessageOutput.printf("[SerialPortManager] HW UART port %d now in use "
"by %s\r\n", port, print(owner));
return true;
}

void SerialPortManagerClass::invalidateBatteryPort()
{
invalidate(Owner::BATTERY);
invalidate(Owner::Battery);
}

void SerialPortManagerClass::invalidateMpptPorts()
Expand All @@ -51,10 +69,12 @@ void SerialPortManagerClass::invalidate(Owner owner)
const char* SerialPortManagerClass::print(Owner owner)
{
switch (owner) {
case BATTERY:
return "BATTERY";
case MPPT:
return "MPPT";
case Owner::Console:
return "Serial Console";
case Owner::Battery:
return "Battery Interface";
case Owner::MPPT:
return "Victron MPPT";
}
return "unknown";
}
33 changes: 18 additions & 15 deletions src/VictronMppt.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,29 +29,32 @@ void VictronMpptClass::updateSettings()

const PinMapping_t& pin = PinMapping.get();

int hwSerialPort = 1;
bool initSuccess = initController(pin.victron_rx, pin.victron_tx, config.Vedirect.VerboseLogging, hwSerialPort);
if (initSuccess) {
hwSerialPort++;
}

initController(pin.victron_rx2, pin.victron_tx2, config.Vedirect.VerboseLogging, hwSerialPort);
// HW UART 1 has always been the designated UART to connect a Victron MPPT
if (!initController(pin.victron_rx, pin.victron_tx,
config.Vedirect.VerboseLogging, 1, 1)) { return; }

// HW UART 2 conflicts with the SDM power meter and the battery interface
if (!initController(pin.victron_rx2, pin.victron_tx2,
config.Vedirect.VerboseLogging, 2, 2)) { return; }

// HW UART 0 is only available on ESP32-S3 with logging over USB CDC, and
// furthermore still conflicts with the battery interface in that case
initController(pin.victron_rx3, pin.victron_tx3,
config.Vedirect.VerboseLogging, 3, 0);
}

bool VictronMpptClass::initController(int8_t rx, int8_t tx, bool logging, int hwSerialPort)
bool VictronMpptClass::initController(int8_t rx, int8_t tx, bool logging,
uint8_t instance, uint8_t hwSerialPort)
{
MessageOutput.printf("[VictronMppt] rx = %d, tx = %d, hwSerialPort = %d\r\n", rx, tx, hwSerialPort);
MessageOutput.printf("[VictronMppt Instance %d] rx = %d, tx = %d, "
"hwSerialPort = %d\r\n", instance, rx, tx, hwSerialPort);

if (rx < 0) {
MessageOutput.printf("[VictronMppt] invalid pin config rx = %d, tx = %d\r\n", rx, tx);
MessageOutput.printf("[VictronMppt Instance %d] invalid pin config\r\n", instance);
return false;
}

if (!SerialPortManager.allocateMpptPort(hwSerialPort)) {
MessageOutput.printf("[VictronMppt] Serial port %d already in use. Initialization aborted!\r\n",
hwSerialPort);
return false;
}
if (!SerialPortManager.allocateMpptPort(hwSerialPort)) { return false; }

auto upController = std::make_unique<VeDirectMpptController>();
upController->init(rx, tx, &MessageOutput, logging, hwSerialPort);
Expand Down
2 changes: 1 addition & 1 deletion src/VictronSmartShunt.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ bool VictronSmartShunt::init(bool verboseLogging)
auto tx = static_cast<gpio_num_t>(pin.battery_tx);
auto rx = static_cast<gpio_num_t>(pin.battery_rx);

VeDirectShunt.init(rx, tx, &MessageOutput, verboseLogging);
VeDirectShunt.init(rx, tx, &MessageOutput, verboseLogging, _hwSerialPort);
return true;
}

Expand Down
2 changes: 2 additions & 0 deletions src/WebApi_device.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -91,6 +91,8 @@ void WebApiDeviceClass::onDeviceAdminGet(AsyncWebServerRequest* request)
victronPinObj["tx"] = pin.victron_tx;
victronPinObj["rx2"] = pin.victron_rx2;
victronPinObj["tx2"] = pin.victron_tx2;
victronPinObj["rx3"] = pin.victron_rx3;
victronPinObj["tx3"] = pin.victron_tx3;

auto batteryPinObj = curPin["battery"].to<JsonObject>();
batteryPinObj["rx"] = pin.battery_rx;
Expand Down
3 changes: 3 additions & 0 deletions src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
#include "InverterSettings.h"
#include "Led_Single.h"
#include "MessageOutput.h"
#include "SerialPortManager.h"
#include "VictronMppt.h"
#include "Battery.h"
#include "Huawei_can.h"
Expand Down Expand Up @@ -96,6 +97,8 @@ void setup()
const auto& pin = PinMapping.get();
MessageOutput.println("done");

SerialPortManager.init();

// Initialize WiFi
MessageOutput.print("Initialize Network... ");
NetworkSettings.init(scheduler);
Expand Down

0 comments on commit 5a1c3af

Please sign in to comment.