rtu: implement modbus sensor read

Read the modbus device config from the Entity Manager configuration and
create the sensor interfaces for related sensor register config.

Tested:
Added new Unit test named test_sensors -
```
> meson test -t 10 -C builddir/ --print-errorlogs --wrapper="valgrind --error-exitcode=1" test_sensors
ninja: Entering directory `/host/repos/Modbus/phosphor-modbus/builddir'
[2/2] Linking target tests/test_sensors
1/1 test_sensors        OK              13.98s

Ok:                1
Fail:              0
```

Tested on Qemu using Mock Modbus Device -
```
root@ventura:~# busctl tree xyz.openbmc_project.ModbusRTU
└─ /xyz
  └─ /xyz/openbmc_project
    ├─ /xyz/openbmc_project/inventory_source
    │ ├─ /xyz/openbmc_project/inventory_source/Heat_Exchanger_12_DevTTYUSB0
    │ ├─ /xyz/openbmc_project/inventory_source/Heat_Exchanger_12_DevTTYUSB1
    │ ├─ /xyz/openbmc_project/inventory_source/Reservoir_Pumping_Unit_12_DevTTYUSB0
    │ └─ /xyz/openbmc_project/inventory_source/Reservoir_Pumping_Unit_12_DevTTYUSB1
    └─ /xyz/openbmc_project/sensors
      └─ /xyz/openbmc_project/sensors/temperature
        ├─ /xyz/openbmc_project/sensors/temperature/Reservoir_Pumping_Unit_12_DevTTYUSB0_RPU_Coolant_Inlet_Temp_C
        ├─ /xyz/openbmc_project/sensors/temperature/Reservoir_Pumping_Unit_12_DevTTYUSB0_RPU_Coolant_Outlet_Temp_C
        ├─ /xyz/openbmc_project/sensors/temperature/Reservoir_Pumping_Unit_12_DevTTYUSB1_RPU_Coolant_Inlet_Temp_C
        └─ /xyz/openbmc_project/sensors/temperature/Reservoir_Pumping_Unit_12_DevTTYUSB1_RPU_Coolant_Outlet_Temp_C

busctl introspect xyz.openbmc_project.ModbusRTU /xyz/openbmc_project/sensors/temperature/Reservoir_Pumping_Unit_12_DevTTYUSB1_RPU_Coolant_Outlet_Temp_C
NAME                                TYPE      SIGNATURE RESULT/VALUE                             FLAGS
org.freedesktop.DBus.Introspectable interface -         -                                        -
.Introspect                         method    -         s                                        -
org.freedesktop.DBus.Peer           interface -         -                                        -
.GetMachineId                       method    -         s                                        -
.Ping                               method    -         -                                        -
org.freedesktop.DBus.Properties     interface -         -                                        -
.Get                                method    ss        v                                        -
.GetAll                             method    s         a{sv}                                    -
.Set                                method    ssv       -                                        -
.PropertiesChanged                  signal    sa{sv}as  -                                        -
xyz.openbmc_project.Sensor.Value    interface -         -                                        -
.MaxValue                           property  d         nan                                      emits-change writable
.MinValue                           property  d         nan                                      emits-change writable
.Unit                               property  s         "xyz.openbmc_project.Sensor.Value.Unit.… emits-change writable
.Value                              property  d         1670.6                                   emits-change writable
```

Change-Id: I1368e8df5999b5cee9ac19d185ee110a9ecc3021
Signed-off-by: Jagpal Singh Gill <paligill@gmail.com>
diff --git a/rtu/device/base_config.cpp b/rtu/device/base_config.cpp
new file mode 100644
index 0000000..d9e7e4f
--- /dev/null
+++ b/rtu/device/base_config.cpp
@@ -0,0 +1,362 @@
+#include "base_config.hpp"
+
+#include "common/entity_manager_interface.hpp"
+
+#include <phosphor-logging/lg2.hpp>
+#include <xyz/openbmc_project/Inventory/Item/client.hpp>
+#include <xyz/openbmc_project/State/Leak/Detector/aserver.hpp>
+
+#include <flat_map>
+
+namespace phosphor::modbus::rtu::device::config
+{
+
+PHOSPHOR_LOG2_USING;
+
+using BasicVariantType =
+    std::variant<std::vector<std::string>, std::vector<uint8_t>, std::string,
+                 int64_t, uint64_t, double, int32_t, uint32_t, int16_t,
+                 uint16_t, uint8_t, bool>;
+using InventoryBaseConfigMap = std::flat_map<std::string, BasicVariantType>;
+using InventoryData = std::flat_map<std::string, InventoryBaseConfigMap>;
+using ManagedObjectType =
+    std::flat_map<sdbusplus::message::object_path, InventoryData>;
+
+static constexpr std::array<std::pair<std::string_view, Parity>, 3>
+    validParities = {
+        {{"Odd", Parity::odd}, {"Even", Parity::even}, {"None", Parity::none}}};
+
+template <typename T>
+auto getValue(const InventoryBaseConfigMap& configMap, const std::string& key,
+              const std::string& contextName) -> T
+{
+    auto iter = configMap.find(key);
+    if (iter == configMap.end())
+    {
+        throw std::runtime_error(
+            "Missing property " + key + " for " + contextName);
+    }
+
+    try
+    {
+        return std::get<T>(iter->second);
+    }
+    catch (const std::bad_variant_access& ex)
+    {
+        throw std::runtime_error(
+            "Incorrect type for property " + key + " in " + contextName);
+    }
+}
+
+static inline auto getDataParity(Config& config,
+                                 const InventoryBaseConfigMap& configMap)
+    -> void
+{
+    auto receivedParity =
+        getValue<std::string>(configMap, "DataParity", config.name);
+
+    for (const auto& [parityStr, parity] : validParities)
+    {
+        if (parityStr == receivedParity)
+        {
+            config.parity = parity;
+            break;
+        }
+    }
+
+    if (config.parity == Parity::unknown)
+    {
+        throw std::runtime_error(
+            "Invalid parity " + receivedParity + " for " + config.name);
+    }
+}
+
+static auto processDeviceInterface(Config& config,
+                                   const InventoryBaseConfigMap& configMap)
+    -> void
+{
+    debug("Processing device config");
+
+    config.name = getValue<std::string>(configMap, "Name", config.name);
+
+    std::replace(config.name.begin(), config.name.end(), ' ', '_');
+
+    config.address = getValue<uint64_t>(configMap, "Address", config.name);
+
+    getDataParity(config, configMap);
+
+    config.baudRate = getValue<uint64_t>(configMap, "BaudRate", config.name);
+
+    config.portName =
+        getValue<std::string>(configMap, "SerialPort", config.name);
+
+    getValue<std::string>(configMap, "Type", config.name);
+}
+
+static const auto sensorTypes = std::unordered_map<
+    std::string_view, std::pair<std::string_view, SensorValueIntf::Unit>>{
+    {"FanTach",
+     {SensorValueIntf::namespace_path::fan_tach, SensorValueIntf::Unit::RPMS}},
+    {"LiquidFlow",
+     {SensorValueIntf::namespace_path::liquidflow, SensorValueIntf::Unit::LPM}},
+    {"Power",
+     {SensorValueIntf::namespace_path::power, SensorValueIntf::Unit::Watts}},
+    {"Pressure",
+     {SensorValueIntf::namespace_path::pressure,
+      SensorValueIntf::Unit::Pascals}},
+    {"Temperature",
+     {SensorValueIntf::namespace_path::temperature,
+      SensorValueIntf::Unit::DegreesC}},
+};
+
+static const auto formatTypes =
+    std::unordered_map<std::string_view, SensorFormat>{
+        {"Integer", SensorFormat::integer},
+        {"Float", SensorFormat::floatingPoint}};
+
+static auto processRegisterType(SensorRegister& sensorRegister,
+                                const InventoryBaseConfigMap& configMap) -> void
+{
+    auto registerType =
+        getValue<std::string>(configMap, "RegisterType", sensorRegister.name);
+
+    auto type = sensorTypes.find(registerType);
+    if (type == sensorTypes.end())
+    {
+        throw std::runtime_error("Invalid RegisterType " + registerType +
+                                 " for " + sensorRegister.name);
+    }
+    sensorRegister.pathSuffix = type->second.first;
+    sensorRegister.unit = type->second.second;
+}
+
+static auto processRegisterFormat(SensorRegister& sensorRegister,
+                                  const InventoryBaseConfigMap& configMap)
+    -> void
+{
+    auto format =
+        getValue<std::string>(configMap, "Format", sensorRegister.name);
+
+    auto formatIter = formatTypes.find(format);
+    if (formatIter == formatTypes.end())
+    {
+        throw std::runtime_error(
+            "Invalid Format " + format + " for " + sensorRegister.name);
+    }
+    sensorRegister.format = formatIter->second;
+}
+
+static auto processSensorRegistersInterface(
+    Config& config, const InventoryBaseConfigMap& configMap) -> void
+{
+    SensorRegister sensorRegister = {};
+
+    sensorRegister.name = getValue<std::string>(configMap, "Name", config.name);
+
+    processRegisterType(sensorRegister, configMap);
+
+    sensorRegister.offset =
+        getValue<uint64_t>(configMap, "Address", config.name);
+
+    sensorRegister.size = getValue<uint64_t>(configMap, "Size", config.name);
+
+    sensorRegister.precision =
+        getValue<uint64_t>(configMap, "Precision", config.name);
+
+    sensorRegister.shift = getValue<double>(configMap, "Shift", config.name);
+
+    sensorRegister.scale = getValue<double>(configMap, "Scale", config.name);
+
+    sensorRegister.isSigned = getValue<bool>(configMap, "Signed", config.name);
+
+    processRegisterFormat(sensorRegister, configMap);
+
+    config.sensorRegisters.emplace_back(sensorRegister);
+}
+
+static const auto statusBitTypes =
+    std::unordered_map<std::string_view, StatusType>{
+        {"ControllerFailure", StatusType::controllerFailure},
+        {"FanFailure", StatusType::fanFailure},
+        {"FilterFailure", StatusType::filterFailure},
+        {"PowerFault", StatusType::powerFault},
+        {"PumpFailure", StatusType::pumpFailure},
+        {"LeakDetectedCritical", StatusType::leakDetectedCritical},
+        {"LeakDetectedWarning", StatusType::leakDetectedWarning},
+        {"SensorFailure", StatusType::sensorFailure},
+        {"SensorReadingCritical", StatusType::sensorReadingCritical},
+        {"SensorReadingWarning", StatusType::sensorReadingWarning}};
+
+static auto processStatusBitsInterface(Config& config,
+                                       const InventoryBaseConfigMap& configMap)
+    -> void
+{
+    debug("Processing StatusBits for {NAME}", "NAME", config.name);
+
+    StatusBit statusBit = {};
+
+    statusBit.name = getValue<std::string>(configMap, "Name", config.name);
+
+    auto type = getValue<std::string>(configMap, "StatusType", config.name);
+    auto typeIter = statusBitTypes.find(type);
+    if (typeIter == statusBitTypes.end())
+    {
+        throw std::runtime_error(
+            "Invalid StatusType " + type + " for " + statusBit.name);
+    }
+    statusBit.type = typeIter->second;
+
+    statusBit.bitPosition =
+        getValue<uint64_t>(configMap, "BitPosition", config.name);
+
+    statusBit.value = getValue<bool>(configMap, "Value", config.name);
+
+    auto address = getValue<uint64_t>(configMap, "Address", config.name);
+
+    config.statusRegisters[address].emplace_back(statusBit);
+}
+
+static const auto firmwareRegisterTypes =
+    std::unordered_map<std::string_view, FirmwareRegisterType>{
+        {"Version", FirmwareRegisterType::version},
+        {"Update", FirmwareRegisterType::update}};
+
+static auto processFirmwareRegistersInterface(
+    Config& config, const InventoryBaseConfigMap& configMap) -> void
+{
+    debug("Processing FirmwareRegisters for {NAME}", "NAME", config.name);
+
+    FirmwareRegister firmwareRegister = {};
+
+    firmwareRegister.name =
+        getValue<std::string>(configMap, "Name", config.name);
+
+    firmwareRegister.offset =
+        getValue<uint64_t>(configMap, "Address", firmwareRegister.name);
+
+    firmwareRegister.size =
+        getValue<uint64_t>(configMap, "Size", firmwareRegister.name);
+
+    auto registerType =
+        getValue<std::string>(configMap, "RegisterType", firmwareRegister.name);
+    auto registerTypeIter = firmwareRegisterTypes.find(registerType);
+    if (registerTypeIter == firmwareRegisterTypes.end())
+    {
+        throw std::runtime_error("Invalid RegisterType " + registerType +
+                                 " for " + firmwareRegister.name);
+    }
+    firmwareRegister.type = registerTypeIter->second;
+
+    config.firmwareRegisters.emplace_back(firmwareRegister);
+}
+
+static auto printConfig(const Config& config) -> void
+{
+    info("Device Config for {NAME}: {ADDRESS} {PORT} {INV_PATH}", "NAME",
+         config.name, "ADDRESS", config.address, "PORT", config.portName,
+         "INV_PATH", config.inventoryPath);
+
+    for (const auto& sensorRegister : config.sensorRegisters)
+    {
+        info(
+            "Sensor Register {NAME} {ADDRESS} {SIZE} {PRECISION} {SCALE} {SIGNED} {FORMAT} {UNIT} {PATH_SUFFIX}",
+            "NAME", sensorRegister.name, "ADDRESS", sensorRegister.offset,
+            "SIZE", sensorRegister.size, "PRECISION", sensorRegister.precision,
+            "SCALE", sensorRegister.scale, "SIGNED", sensorRegister.isSigned,
+            "FORMAT", sensorRegister.format, "UNIT", sensorRegister.unit,
+            "PATH_SUFFIX", sensorRegister.pathSuffix);
+    }
+
+    for (const auto& [address, statusBits] : config.statusRegisters)
+    {
+        for (const auto& statusBit : statusBits)
+        {
+            info("Status Bit {NAME} {ADDRESS} {BIT_POSITION} {VALUE} {TYPE}",
+                 "NAME", statusBit.name, "ADDRESS", address, "BIT_POSITION",
+                 statusBit.bitPosition, "VALUE", statusBit.value, "TYPE",
+                 statusBit.type);
+        }
+    }
+
+    for (const auto& firmwareRegister : config.firmwareRegisters)
+    {
+        info("Firmware Register {NAME} {ADDRESS} {SIZE} {TYPE}", "NAME",
+             firmwareRegister.name, "ADDRESS", firmwareRegister.offset, "SIZE",
+             firmwareRegister.size, "TYPE", firmwareRegister.type);
+    }
+}
+
+static auto getConfigSubTree(Config& config, const std::string& interfaceName,
+                             const InventoryData& deviceConfig) -> void
+{
+    std::string firmwareRegistersInterface =
+        interfaceName + ".FirmwareRegisters";
+    std::string sensorRegistersInterface = interfaceName + ".SensorRegisters";
+    std::string statusBitsInterface = interfaceName + ".StatusBits";
+
+    for (const auto& [curInterface, interfaceConfig] : deviceConfig)
+    {
+        if (curInterface == interfaceName)
+        {
+            processDeviceInterface(config, interfaceConfig);
+        }
+        else if (curInterface.starts_with(sensorRegistersInterface))
+        {
+            processSensorRegistersInterface(config, interfaceConfig);
+        }
+        else if (curInterface.starts_with(statusBitsInterface))
+        {
+            processStatusBitsInterface(config, interfaceConfig);
+        }
+        else if (curInterface.starts_with(firmwareRegistersInterface))
+        {
+            processFirmwareRegistersInterface(config, interfaceConfig);
+        }
+    }
+}
+
+auto updateBaseConfig(sdbusplus::async::context& ctx,
+                      const sdbusplus::message::object_path& objectPath,
+                      const std::string& interfaceName, Config& config)
+    -> sdbusplus::async::task<bool>
+{
+    config.inventoryPath = objectPath.parent_path();
+
+    using InventoryIntf =
+        sdbusplus::client::xyz::openbmc_project::inventory::Item<>;
+
+    constexpr auto entityManager =
+        sdbusplus::async::proxy()
+            .service(entity_manager::EntityManagerInterface::serviceName)
+            .path(InventoryIntf::namespace_path)
+            .interface("org.freedesktop.DBus.ObjectManager");
+
+    for (const auto& [path, deviceConfig] :
+         co_await entityManager.call<ManagedObjectType>(ctx,
+                                                        "GetManagedObjects"))
+    {
+        if (path.str != objectPath.str)
+        {
+            debug("Skipping device {PATH}", "PATH", path.str);
+            continue;
+        }
+        debug("Processing device {PATH}", "PATH", path.str);
+
+        try
+        {
+            getConfigSubTree(config, interfaceName, deviceConfig);
+        }
+        catch (std::exception& e)
+        {
+            error("Failed to process device {PATH} with {ERROR}", "PATH",
+                  path.str, "ERROR", e);
+            co_return false;
+        }
+    }
+
+    printConfig(config);
+
+    co_return true;
+}
+
+} // namespace phosphor::modbus::rtu::device::config
diff --git a/rtu/device/base_config.hpp b/rtu/device/base_config.hpp
new file mode 100644
index 0000000..595c0df
--- /dev/null
+++ b/rtu/device/base_config.hpp
@@ -0,0 +1,102 @@
+#pragma once
+
+#include "modbus/modbus.hpp"
+
+#include <xyz/openbmc_project/Sensor/Value/client.hpp>
+
+namespace phosphor::modbus::rtu::device
+{
+
+namespace ModbusIntf = phosphor::modbus::rtu;
+
+namespace config
+{
+
+using SensorValueIntf =
+    sdbusplus::client::xyz::openbmc_project::sensor::Value<>;
+
+enum class SensorFormat
+{
+    floatingPoint,
+    integer,
+    unknown
+};
+
+struct SensorRegister
+{
+    std::string name = "unknown";
+    std::string pathSuffix = "unknown";
+    SensorValueIntf::Unit unit;
+    uint16_t offset = 0;
+    uint8_t size = 0;
+    uint8_t precision = 0;
+    double scale = 1.0;
+    double shift = 0.0;
+    bool isSigned = false;
+    SensorFormat format = SensorFormat::unknown;
+};
+
+enum class StatusType
+{
+    controllerFailure,
+    fanFailure,
+    filterFailure,
+    powerFault,
+    pumpFailure,
+    leakDetectedCritical,
+    leakDetectedWarning,
+    sensorFailure,
+    sensorReadingCritical,
+    sensorReadingWarning,
+    unknown
+};
+
+struct StatusBit
+{
+    std::string name = "unknown";
+    StatusType type = StatusType::unknown;
+    uint8_t bitPosition = 0;
+    bool value = false;
+};
+
+enum class FirmwareRegisterType
+{
+    version,
+    update,
+    unknown
+};
+
+struct FirmwareRegister
+{
+    std::string name = "unknown";
+    FirmwareRegisterType type = FirmwareRegisterType::unknown;
+    uint16_t offset = 0;
+    uint8_t size = 0;
+};
+
+struct Config
+{
+    using sensor_registers_t = std::vector<SensorRegister>;
+    using status_registers_t =
+        std::unordered_map<uint16_t, std::vector<StatusBit>>;
+    using firmware_registers_t = std::vector<FirmwareRegister>;
+
+    uint8_t address = 0;
+    ModbusIntf::Parity parity = ModbusIntf::Parity::unknown;
+    uint32_t baudRate = 0;
+    std::string name = "unknown";
+    std::string portName = "unknown";
+    sdbusplus::message::object_path inventoryPath;
+    sensor_registers_t sensorRegisters;
+    status_registers_t statusRegisters;
+    firmware_registers_t firmwareRegisters;
+};
+
+auto updateBaseConfig(sdbusplus::async::context& ctx,
+                      const sdbusplus::message::object_path& objectPath,
+                      const std::string& interfaceName, Config& config)
+    -> sdbusplus::async::task<bool>;
+
+} // namespace config
+
+} // namespace phosphor::modbus::rtu::device
diff --git a/rtu/device/base_device.cpp b/rtu/device/base_device.cpp
new file mode 100644
index 0000000..73d1ca6
--- /dev/null
+++ b/rtu/device/base_device.cpp
@@ -0,0 +1,159 @@
+#include "base_device.hpp"
+
+#include <phosphor-logging/lg2.hpp>
+
+#include <numeric>
+
+namespace phosphor::modbus::rtu::device
+{
+
+PHOSPHOR_LOG2_USING;
+
+BaseDevice::BaseDevice(sdbusplus::async::context& ctx,
+                       const config::Config& config, PortIntf& serialPort) :
+    ctx(ctx), config(config), serialPort(serialPort)
+{
+    createSensors();
+
+    info("Successfully created device {NAME}", "NAME", config.name);
+}
+
+static auto getObjectPath(const std::string& sensorType,
+                          const std::string& sensorName)
+    -> sdbusplus::message::object_path
+{
+    return sdbusplus::message::object_path(
+        std::string(SensorValueIntf::namespace_path::value) + "/" + sensorType +
+        "/" + sensorName);
+}
+
+auto BaseDevice::createSensors() -> void
+{
+    for (const auto& sensorRegister : config.sensorRegisters)
+    {
+        SensorValueIntf::properties_t initProperties = {
+            std::numeric_limits<double>::quiet_NaN(),
+            std::numeric_limits<double>::quiet_NaN(),
+            std::numeric_limits<double>::quiet_NaN(), sensorRegister.unit};
+
+        auto sensorPath = getObjectPath(
+            sensorRegister.pathSuffix, config.name + "_" + sensorRegister.name);
+
+        auto sensor = std::make_unique<SensorValueIntf>(
+            ctx, sensorPath.str.c_str(), initProperties);
+
+        sensor->emit_added();
+
+        sensors.emplace(sensorRegister.name, std::move(sensor));
+    }
+
+    return;
+}
+
+static auto getRawIntegerFromRegister(const std::vector<uint16_t>& reg,
+                                      bool sign) -> int64_t
+{
+    if (reg.empty())
+    {
+        return 0;
+    }
+
+    uint64_t accumulator = 0;
+    for (auto val : reg)
+    {
+        accumulator = (accumulator << 16) | val;
+    }
+
+    int64_t result = 0;
+
+    if (sign)
+    {
+        if (reg.size() == 1)
+        {
+            result = static_cast<int16_t>(accumulator);
+        }
+        else if (reg.size() == 2)
+        {
+            result = static_cast<int32_t>(accumulator);
+        }
+        else
+        {
+            result = static_cast<int64_t>(accumulator);
+        }
+    }
+    else
+    {
+        if (reg.size() == 1)
+        {
+            result = static_cast<uint16_t>(accumulator);
+        }
+        else if (reg.size() == 2)
+        {
+            result = static_cast<uint32_t>(accumulator);
+        }
+        else
+        {
+            result = static_cast<int64_t>(accumulator);
+        }
+    }
+
+    return result;
+}
+
+auto BaseDevice::readSensorRegisters() -> sdbusplus::async::task<void>
+{
+    while (!ctx.stop_requested())
+    {
+        for (const auto& sensorRegister : config.sensorRegisters)
+        {
+            auto sensor = sensors.find(sensorRegister.name);
+            if (sensor == sensors.end())
+            {
+                error("Sensor not found for {NAME}", "NAME",
+                      sensorRegister.name);
+                continue;
+            }
+
+            if (sensorRegister.size > 4)
+            {
+                error("Unsupported size for register {NAME}", "NAME",
+                      sensorRegister.name);
+                continue;
+            }
+
+            auto registers = std::vector<uint16_t>(sensorRegister.size);
+            auto ret = co_await serialPort.readHoldingRegisters(
+                config.address, sensorRegister.offset, config.baudRate,
+                config.parity, registers);
+            if (!ret)
+            {
+                error(
+                    "Failed to read holding registers {NAME} for {DEVICE_ADDRESS}",
+                    "NAME", sensorRegister.name, "DEVICE_ADDRESS",
+                    config.address);
+                continue;
+            }
+
+            double regVal = static_cast<double>(
+                getRawIntegerFromRegister(registers, sensorRegister.isSigned));
+            if (sensorRegister.format == config::SensorFormat::floatingPoint)
+            {
+                regVal = sensorRegister.shift +
+                         (sensorRegister.scale *
+                          (regVal / (1ULL << sensorRegister.precision)));
+            }
+
+            sensor->second->value(regVal);
+        }
+
+        constexpr auto pollInterval = 3;
+        co_await sdbusplus::async::sleep_for(
+            ctx, std::chrono::seconds(pollInterval));
+        debug("Polling sensors for {NAME} in {INTERVAL} seconds", "NAME",
+              config.name, "INTERVAL", pollInterval);
+    }
+
+    co_return;
+}
+
+} // namespace phosphor::modbus::rtu::device
diff --git a/rtu/device/base_device.hpp b/rtu/device/base_device.hpp
new file mode 100644
index 0000000..a64d708
--- /dev/null
+++ b/rtu/device/base_device.hpp
@@ -0,0 +1,40 @@
+#pragma once
+
+#include "base_config.hpp"
+#include "modbus/modbus.hpp"
+#include "port/base_port.hpp"
+
+#include <sdbusplus/async.hpp>
+#include <xyz/openbmc_project/Sensor/Value/aserver.hpp>
+
+namespace phosphor::modbus::rtu::device
+{
+
+class Device;
+
+using SensorValueIntf =
+    sdbusplus::aserver::xyz::openbmc_project::sensor::Value<Device>;
+using PortIntf = phosphor::modbus::rtu::port::BasePort;
+
+class BaseDevice
+{
+  public:
+    BaseDevice() = delete;
+
+    explicit BaseDevice(sdbusplus::async::context& ctx,
+                        const config::Config& config, PortIntf& serialPort);
+
+    auto readSensorRegisters() -> sdbusplus::async::task<void>;
+
+  private:
+    auto createSensors() -> void;
+
+    using sensors_map_t =
+        std::unordered_map<std::string, std::unique_ptr<SensorValueIntf>>;
+    sdbusplus::async::context& ctx;
+    const config::Config config;
+    PortIntf& serialPort;
+    sensors_map_t sensors;
+};
+
+} // namespace phosphor::modbus::rtu::device
diff --git a/rtu/device/device_factory.cpp b/rtu/device/device_factory.cpp
new file mode 100644
index 0000000..d707952
--- /dev/null
+++ b/rtu/device/device_factory.cpp
@@ -0,0 +1,54 @@
+#include "device_factory.hpp"
+
+#include "reservoir_pump_unit.hpp"
+
+#include <string>
+#include <vector>
+
+namespace phosphor::modbus::rtu::device
+{
+
+using ReservoirPumpUnitIntf = phosphor::modbus::rtu::device::ReservoirPumpUnit;
+
+auto DeviceFactory::getInterfaces() -> std::vector<std::string>
+{
+    std::vector<std::string> interfaces{};
+
+    auto rpuInterfaces = ReservoirPumpUnitIntf::getInterfaces();
+    interfaces.insert(interfaces.end(), rpuInterfaces.begin(),
+                      rpuInterfaces.end());
+
+    return interfaces;
+}
+
+auto DeviceFactory::getConfig(sdbusplus::async::context& ctx,
+                              const sdbusplus::message::object_path& objectPath,
+                              const std::string& interfaceName)
+    -> sdbusplus::async::task<std::optional<config::DeviceFactoryConfig>>
+{
+    auto rpuInterfaces = ReservoirPumpUnitIntf::getInterfaces();
+    if (rpuInterfaces.find(interfaceName) != rpuInterfaces.end())
+    {
+        co_return co_await ReservoirPumpUnitIntf::getConfig(ctx, objectPath,
+                                                            interfaceName);
+    }
+
+    co_return std::nullopt;
+}
+
+auto DeviceFactory::create(sdbusplus::async::context& ctx,
+                           const config::DeviceFactoryConfig& config,
+                           PortIntf& serialPort) -> std::unique_ptr<BaseDevice>
+{
+    switch (config.deviceType)
+    {
+        case config::DeviceType::reservoirPumpUnit:
+            return std::make_unique<ReservoirPumpUnit>(ctx, config, serialPort);
+        default:
+            break;
+    }
+
+    return nullptr;
+}
+
+} // namespace phosphor::modbus::rtu::device
diff --git a/rtu/device/device_factory.hpp b/rtu/device/device_factory.hpp
new file mode 100644
index 0000000..5dca705
--- /dev/null
+++ b/rtu/device/device_factory.hpp
@@ -0,0 +1,50 @@
+#pragma once
+
+#include "base_device.hpp"
+
+namespace phosphor::modbus::rtu::device
+{
+
+namespace config
+{
+
+enum class DeviceType
+{
+    reservoirPumpUnit,
+    heatExchanger,
+    flowMeter,
+    unknown
+};
+
+enum class DeviceModel
+{
+    RDF040DSS5193E0,
+    unknown
+};
+
+struct DeviceFactoryConfig : public Config
+{
+    DeviceType deviceType = DeviceType::unknown;
+    DeviceModel deviceModel = DeviceModel::unknown;
+};
+
+} // namespace config
+
+class DeviceFactory
+{
+  public:
+    DeviceFactory() = delete;
+
+    static auto getInterfaces() -> std::vector<std::string>;
+
+    static auto getConfig(sdbusplus::async::context& ctx,
+                          const sdbusplus::message::object_path& objectPath,
+                          const std::string& interfaceName)
+        -> sdbusplus::async::task<std::optional<config::DeviceFactoryConfig>>;
+
+    static auto create(sdbusplus::async::context& ctx,
+                       const config::DeviceFactoryConfig& config,
+                       PortIntf& serialPort) -> std::unique_ptr<BaseDevice>;
+};
+
+} // namespace phosphor::modbus::rtu::device
diff --git a/rtu/device/reservoir_pump_unit.cpp b/rtu/device/reservoir_pump_unit.cpp
new file mode 100644
index 0000000..58debee
--- /dev/null
+++ b/rtu/device/reservoir_pump_unit.cpp
@@ -0,0 +1,68 @@
+#include "reservoir_pump_unit.hpp"
+
+#include "device_factory.hpp"
+
+#include <phosphor-logging/lg2.hpp>
+
+namespace phosphor::modbus::rtu::device
+{
+
+PHOSPHOR_LOG2_USING;
+
+static constexpr auto ModbusRDF040DSS5193E0ReservoirPumpUnitInterface =
+    "xyz.openbmc_project.Configuration.ModbusRDF040DSS5193E0ReservoirPumpUnit";
+
+static const std::unordered_map<std::string_view, config::DeviceModel>
+    validDevices = {{ModbusRDF040DSS5193E0ReservoirPumpUnitInterface,
+                     config::DeviceModel::RDF040DSS5193E0}};
+
+ReservoirPumpUnit::ReservoirPumpUnit(sdbusplus::async::context& ctx,
+                                     const config::Config& config,
+                                     PortIntf& serialPort) :
+    BaseDevice(ctx, config, serialPort)
+{
+    info("Reservoir pump unit {NAME} created successfully", "NAME",
+         config.name);
+}
+
+auto ReservoirPumpUnit::getInterfaces() -> std::unordered_set<std::string>
+{
+    return {ModbusRDF040DSS5193E0ReservoirPumpUnitInterface};
+}
+
+auto ReservoirPumpUnit::getConfig(
+    sdbusplus::async::context& ctx,
+    const sdbusplus::message::object_path& objectPath,
+    const std::string& interfaceName)
+    -> sdbusplus::async::task<std::optional<config::DeviceFactoryConfig>>
+{
+    config::DeviceFactoryConfig config{};
+
+    auto res = co_await config::updateBaseConfig(ctx, objectPath, interfaceName,
+                                                 config);
+    if (!res)
+    {
+        co_return std::nullopt;
+    }
+
+    for (const auto& [deviceInterface, deviceModel] : validDevices)
+    {
+        if (interfaceName == deviceInterface)
+        {
+            config.deviceModel = deviceModel;
+        }
+    }
+
+    if (config.deviceModel == config::DeviceModel::unknown)
+    {
+        error("Invalid device model {MODEL} for {NAME}", "MODEL", interfaceName,
+              "NAME", config.name);
+        co_return std::nullopt;
+    }
+
+    config.deviceType = config::DeviceType::reservoirPumpUnit;
+
+    co_return config;
+}
+
+} // namespace phosphor::modbus::rtu::device
diff --git a/rtu/device/reservoir_pump_unit.hpp b/rtu/device/reservoir_pump_unit.hpp
new file mode 100644
index 0000000..19240f0
--- /dev/null
+++ b/rtu/device/reservoir_pump_unit.hpp
@@ -0,0 +1,32 @@
+#pragma once
+
+#include "base_device.hpp"
+
+#include <unordered_set>
+
+namespace phosphor::modbus::rtu::device
+{
+
+namespace config
+{
+
+struct DeviceFactoryConfig;
+
+} // namespace config
+
+class ReservoirPumpUnit : public BaseDevice
+{
+  public:
+    explicit ReservoirPumpUnit(sdbusplus::async::context& ctx,
+                               const config::Config& config,
+                               PortIntf& serialPort);
+
+    static auto getInterfaces() -> std::unordered_set<std::string>;
+
+    static auto getConfig(sdbusplus::async::context& ctx,
+                          const sdbusplus::message::object_path& objectPath,
+                          const std::string& interfaceName)
+        -> sdbusplus::async::task<std::optional<config::DeviceFactoryConfig>>;
+};
+
+} // namespace phosphor::modbus::rtu::device