Skip to content

Commit

Permalink
Publish motor current for chicken-door
Browse files Browse the repository at this point in the history
  • Loading branch information
lptr committed Aug 16, 2024
1 parent 47ee85d commit 858a64f
Show file tree
Hide file tree
Showing 13 changed files with 132 additions and 75 deletions.
4 changes: 2 additions & 2 deletions src/devices/UglyDucklingMk4.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -96,8 +96,8 @@ class UglyDucklingMk4 : public DeviceDefinition<Mk4Config> {
pins::VALVE_SLEEP
};

const ServiceRef<PwmMotorDriver> motor { "motor", motorDriver };
const std::list<ServiceRef<PwmMotorDriver>> motors { motor };
const ServiceRef<CurrentSensingMotorDriver> motor { "motor", motorDriver };
const std::list<ServiceRef<CurrentSensingMotorDriver>> motors { motor };

ValveFactory valveFactory { motors, ValveControlStrategyType::NormallyClosed };
FlowMeterFactory flowMeterFactory;
Expand Down
6 changes: 3 additions & 3 deletions src/devices/UglyDucklingMk5.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -108,9 +108,9 @@ class UglyDucklingMk5 : public DeviceDefinition<Mk5Config> {
pins::NSLEEP
};

const ServiceRef<PwmMotorDriver> motorA { "a", motorADriver };
const ServiceRef<PwmMotorDriver> motorB { "b", motorBDriver };
const std::list<ServiceRef<PwmMotorDriver>> motors { motorA, motorB };
const ServiceRef<CurrentSensingMotorDriver> motorA { "a", motorADriver };
const ServiceRef<CurrentSensingMotorDriver> motorB { "b", motorBDriver };
const std::list<ServiceRef<CurrentSensingMotorDriver>> motors { motorA, motorB };

ValveFactory valveFactory { motors, ValveControlStrategyType::Latching };
FlowMeterFactory flowMeterFactory;
Expand Down
11 changes: 8 additions & 3 deletions src/devices/UglyDucklingMk6.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
#include <kernel/Kernel.hpp>
#include <kernel/Service.hpp>
#include <kernel/drivers/BatteryDriver.hpp>
#include <kernel/drivers/CurrentSenseDriver.hpp>
#include <kernel/drivers/Drv8833Driver.hpp>
#include <kernel/drivers/LedDriver.hpp>

Expand Down Expand Up @@ -119,9 +120,13 @@ class UglyDucklingMk6 : public DeviceDefinition<Mk6Config> {
config.motorNSleepPin.get()
};

const ServiceRef<PwmMotorDriver> motorA { "a", motorDriver.getMotorA() };
const ServiceRef<PwmMotorDriver> motorB { "b", motorDriver.getMotorB() };
const std::list<ServiceRef<PwmMotorDriver>> motors { motorA, motorB };
SimpleCurrentSenseDriver currentSense { pins::DIPROPI };
ExternalCurrentSensingMotorDriver motorADriver { motorDriver.getMotorA(), currentSense };
ExternalCurrentSensingMotorDriver motorBDriver { motorDriver.getMotorB(), currentSense };

const ServiceRef<CurrentSensingMotorDriver> motorA { "a", motorADriver };
const ServiceRef<CurrentSensingMotorDriver> motorB { "b", motorBDriver };
const std::list<ServiceRef<CurrentSensingMotorDriver>> motors { motorA, motorB };

ValveFactory valveFactory { motors, ValveControlStrategyType::Latching };
FlowMeterFactory flowMeterFactory;
Expand Down
11 changes: 8 additions & 3 deletions src/devices/UglyDucklingMk7.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -113,9 +113,14 @@ class UglyDucklingMk7 : public DeviceDefinition<Mk7Config> {
pins::LOADEN,
};

const ServiceRef<PwmMotorDriver> motorA { "a", motorDriver.getMotorA() };
const ServiceRef<PwmMotorDriver> motorB { "b", motorDriver.getMotorB() };
const std::list<ServiceRef<PwmMotorDriver>> motors { motorA, motorB };
// TODO Implement proper current sensing for MK7
SimpleCurrentSenseDriver currentSense { pins::IOA1 };
ExternalCurrentSensingMotorDriver motorADriver { motorDriver.getMotorA(), currentSense };
ExternalCurrentSensingMotorDriver motorBDriver { motorDriver.getMotorB(), currentSense };

const ServiceRef<CurrentSensingMotorDriver> motorA { "a", motorADriver };
const ServiceRef<CurrentSensingMotorDriver> motorB { "b", motorBDriver };
const std::list<ServiceRef<CurrentSensingMotorDriver>> motors { motorA, motorB };

ValveFactory valveFactory { motors, ValveControlStrategyType::Latching };
FlowMeterFactory flowMeterFactory;
Expand Down
29 changes: 29 additions & 0 deletions src/kernel/drivers/CurrentSenseDriver.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
#pragma once

#include <Arduino.h>

namespace farmhub::kernel::drivers {
class CurrentSenseDriver {

public:
virtual double readCurrent() const = 0;
};

class SimpleCurrentSenseDriver
: public CurrentSenseDriver {
public:
SimpleCurrentSenseDriver(gpio_num_t pin, double scale = 4096)
: pin(pin)
, scale(scale) {
pinMode(pin, INPUT);
}

double readCurrent() const override {
return analogRead(pin) / scale;
}

private:
gpio_num_t pin;
double scale;
};
} // namespace farmhub::kernel::drivers
7 changes: 6 additions & 1 deletion src/kernel/drivers/Drv8801Driver.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
#include <Arduino.h>

#include <kernel/PwmManager.hpp>
#include <kernel/drivers/CurrentSenseDriver.hpp>
#include <kernel/drivers/MotorDriver.hpp>

using namespace std::chrono;
Expand All @@ -18,7 +19,7 @@ namespace farmhub::kernel::drivers {
* https://www.ti.com/lit/gpn/DRV8801
*/
class Drv8801Driver
: public PwmMotorDriver {
: public CurrentSensingMotorDriver {

private:
const uint32_t PWM_FREQ = 25000; // 25kHz
Expand Down Expand Up @@ -91,6 +92,10 @@ class Drv8801Driver
return sleeping;
}

double readCurrent() const override {
return analogRead(currentPin) / 4096.0;
}

private:
const gpio_num_t enablePin;
const PwmChannel phaseChannel;
Expand Down
7 changes: 6 additions & 1 deletion src/kernel/drivers/Drv8874Driver.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
#include <Arduino.h>

#include <kernel/PwmManager.hpp>
#include <kernel/drivers/CurrentSenseDriver.hpp>
#include <kernel/drivers/MotorDriver.hpp>

using namespace std::chrono;
Expand All @@ -18,7 +19,7 @@ namespace farmhub::kernel::drivers {
* https://www.ti.com/lit/gpn/DRV8874
*/
class Drv8874Driver
: public PwmMotorDriver {
: public CurrentSensingMotorDriver {

private:
const uint32_t PWM_FREQ = 25000; // 25kHz
Expand Down Expand Up @@ -88,6 +89,10 @@ class Drv8874Driver
return sleeping;
}

double readCurrent() const override {
return analogRead(currentPin) / 4096.0;
}

private:
const PwmChannel in1Channel;
const PwmChannel in2Channel;
Expand Down
28 changes: 28 additions & 0 deletions src/kernel/drivers/MotorDriver.hpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
#pragma once

#include <kernel/drivers/CurrentSenseDriver.hpp>

namespace farmhub::kernel::drivers {

enum class MotorPhase {
Expand All @@ -22,4 +24,30 @@ class PwmMotorDriver {
virtual void drive(MotorPhase phase, double duty = 1) = 0;
};

class CurrentSensingMotorDriver
: public PwmMotorDriver,
public CurrentSenseDriver {
};

class ExternalCurrentSensingMotorDriver
: public CurrentSensingMotorDriver {
public:
ExternalCurrentSensingMotorDriver(PwmMotorDriver& motor, CurrentSenseDriver& currentSense)
: motor(motor)
, currentSense(currentSense) {
}

void drive(MotorPhase phase, double duty = 1) override {
motor.drive(phase, duty);
}

double readCurrent() const override {
return currentSense.readCurrent();
}

private:
PwmMotorDriver& motor;
CurrentSenseDriver& currentSense;
};

} // namespace farmhub::kernel::drivers
41 changes: 0 additions & 41 deletions src/peripherals/Motorized.hpp

This file was deleted.

25 changes: 25 additions & 0 deletions src/peripherals/Peripheral.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -243,4 +243,29 @@ class PeripheralManager
std::list<unique_ptr<PeripheralBase>> peripherals;
};

template <typename T>
class ServiceContainer {
public:
ServiceContainer(const std::list<ServiceRef<T>>& services)
: services(services) {
}

protected:
T& findService(const String& name) {
// If there's only one service and no name is specified, use it
if (name.isEmpty() && services.size() == 1) {
return services.front().get();
}
for (auto& motor : services) {
if (motor.getName() == name) {
return motor.get();
}
}
throw PeripheralCreationException("failed to find service: " + name);
}

private:
const std::list<ServiceRef<T>> services;
};

} // namespace farmhub::peripherals
17 changes: 9 additions & 8 deletions src/peripherals/chicken_door/ChickenDoor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,10 +16,10 @@
#include <kernel/Telemetry.hpp>
#include <kernel/Watchdog.hpp>

#include <kernel/drivers/CurrentSenseDriver.hpp>
#include <kernel/drivers/MotorDriver.hpp>
#include <kernel/drivers/SwitchManager.hpp>

#include <peripherals/Motorized.hpp>
#include <peripherals/Peripheral.hpp>
#include <peripherals/light_sensor/Bh1750.hpp>
#include <peripherals/light_sensor/LightSensor.hpp>
Expand Down Expand Up @@ -95,7 +95,7 @@ class ChickenDoorComponent
shared_ptr<MqttDriver::MqttRoot> mqttRoot,
SleepManager& sleepManager,
SwitchManager& switches,
PwmMotorDriver& motor,
CurrentSensingMotorDriver& motor,
TLightSensorComponent& lightSensor,
gpio_num_t openPin,
gpio_num_t closedPin,
Expand Down Expand Up @@ -155,6 +155,7 @@ class ChickenDoorComponent
telemetry["state"] = lastState;
telemetry["targetState"] = lastTargetState;
telemetry["operationState"] = operationState;
telemetry["current"] = motor.readCurrent();
if (overrideState != DoorState::NONE) {
time_t rawtime = system_clock::to_time_t(overrideUntil);
auto timeinfo = gmtime(&rawtime);
Expand Down Expand Up @@ -319,7 +320,7 @@ class ChickenDoorComponent
}

SleepManager& sleepManager;
PwmMotorDriver& motor;
CurrentSensingMotorDriver& motor;
TLightSensorComponent& lightSensor;

double openLevel = std::numeric_limits<double>::max();
Expand Down Expand Up @@ -363,7 +364,7 @@ class ChickenDoor
uint8_t lightSensorAddress,
SleepManager& sleepManager,
SwitchManager& switches,
PwmMotorDriver& motor,
CurrentSensingMotorDriver& motor,
const ChickenDoorDeviceConfig& config)
: Peripheral<ChickenDoorConfig>(name, mqttRoot)
, lightSensor(
Expand Down Expand Up @@ -423,15 +424,15 @@ class NoLightSensorComponent : public LightSensorComponent {

class ChickenDoorFactory
: public PeripheralFactory<ChickenDoorDeviceConfig, ChickenDoorConfig>,
protected Motorized {
protected ServiceContainer<CurrentSensingMotorDriver> {
public:
ChickenDoorFactory(const std::list<ServiceRef<PwmMotorDriver>>& motors)
ChickenDoorFactory(const std::list<ServiceRef<CurrentSensingMotorDriver>>& motors)
: PeripheralFactory<ChickenDoorDeviceConfig, ChickenDoorConfig>("chicken-door")
, Motorized(motors) {
, ServiceContainer<CurrentSensingMotorDriver>(motors) {
}

unique_ptr<Peripheral<ChickenDoorConfig>> createPeripheral(const String& name, const ChickenDoorDeviceConfig& deviceConfig, shared_ptr<MqttDriver::MqttRoot> mqttRoot, PeripheralServices& services) override {
PwmMotorDriver& motor = findMotor(deviceConfig.motor.get());
CurrentSensingMotorDriver& motor = findService(deviceConfig.motor.get());
auto lightSensorType = deviceConfig.lightSensor.get().type.get();
try {
if (lightSensorType == "bh1750") {
Expand Down
12 changes: 4 additions & 8 deletions src/peripherals/flow_control/FlowControl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@
#include <kernel/PcntManager.hpp>
#include <kernel/SleepManager.hpp>
#include <kernel/drivers/MqttDriver.hpp>
#include <peripherals/Motorized.hpp>
#include <peripherals/Peripheral.hpp>
#include <peripherals/flow_meter/FlowMeterComponent.hpp>
#include <peripherals/flow_meter/FlowMeterConfig.hpp>
Expand Down Expand Up @@ -74,20 +73,20 @@ class FlowControlDeviceConfig

class FlowControlFactory
: public PeripheralFactory<FlowControlDeviceConfig, FlowControlConfig, ValveControlStrategyType>,
protected Motorized {
protected ServiceContainer<CurrentSensingMotorDriver> {
public:
FlowControlFactory(
const std::list<ServiceRef<PwmMotorDriver>>& motors,
const std::list<ServiceRef<CurrentSensingMotorDriver>>& motors,
ValveControlStrategyType defaultStrategy)
: PeripheralFactory<FlowControlDeviceConfig, FlowControlConfig, ValveControlStrategyType>("flow-control", defaultStrategy)
, Motorized(motors) {
, ServiceContainer<CurrentSensingMotorDriver>(motors) {
}

unique_ptr<Peripheral<FlowControlConfig>> createPeripheral(const String& name, const FlowControlDeviceConfig& deviceConfig, shared_ptr<MqttDriver::MqttRoot> mqttRoot, PeripheralServices& services) override {
const ValveDeviceConfig& valveConfig = deviceConfig.valve.get();
const FlowMeterDeviceConfig& flowMeterConfig = deviceConfig.flowMeter.get();

PwmMotorDriver& targetMotor = findMotor(valveConfig.motor.get());
PwmMotorDriver& targetMotor = findService(valveConfig.motor.get());
ValveControlStrategy* strategy;
try {
strategy = createValveControlStrategy(
Expand All @@ -110,9 +109,6 @@ class FlowControlFactory
flowMeterConfig.qFactor.get(),
flowMeterConfig.measurementFrequency.get());
}

private:
const std::list<ServiceRef<PwmMotorDriver>> motors;
};

} // namespace farmhub::peripherals::flow_control
Loading

0 comments on commit 858a64f

Please sign in to comment.