Skip to content

New version with F01 and F02 Handler #166

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 5 commits into
base: main
Choose a base branch
from
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
27 changes: 27 additions & 0 deletions src/Command.cpp
Original file line number Diff line number Diff line change
@@ -9,6 +9,7 @@ const char parameterValue2Code = 'W';
const char elementCode = 'E';
const char timeCode = 'T';
const char modeCode = 'M';
const char numberCode = 'N'; // Edited by Finn
const char msgQueueCode = 'Q';

CommandCodeEnum commandCodeEnum = CODE_UNDEFINED;
@@ -61,6 +62,18 @@ CommandCodeEnum Command::getGCodeEnum(char *code)
// return F03;
//}

// Finn: F01
if (strcmp(code, "F01") == 0 || strcmp(code, "F1") == 0)
{
return F01;
}

// Finn: F02
if (strcmp(code, "F02") == 0 || strcmp(code, "F2") == 0)
{
return F02;
}

if (strcmp(code, "F09") == 0 || strcmp(code, "F9") == 0)
{
return F09;
@@ -230,6 +243,13 @@ void Command::getParameter(char *charPointer)
time = atof(charPointer + 1);
}

// Edited by Finn
if (charPointer[0] == numberCode) {
number = atof(charPointer + 1);
// Serial.print("Set number to: ");
// Serial.println(number);
}

if (charPointer[0] == modeCode)
{
mode = atof(charPointer + 1);
@@ -267,6 +287,8 @@ void Command::print()
Serial.print(element);
Serial.print(", M: ");
Serial.print(mode);
Serial.print(", N: ");
Serial.print(number);

Serial.print(", A: ");
Serial.print(axisSpeedValue[0]);
@@ -346,6 +368,11 @@ long Command::getM()
return mode;
}

long Command::getN() // Edited by Finn
{
return number;
}

long Command::getQ()
{
//msgQueue = 9876;
2 changes: 2 additions & 0 deletions src/Command.h
Original file line number Diff line number Diff line change
@@ -60,6 +60,7 @@ class Command
long getT();
long getE();
long getM();
long getN(); // Edited by Finn
long getQ();

void printQAndNewLine();
@@ -77,6 +78,7 @@ class Command
long element = 0;
long time = 0;
long mode = 0;
long number = 0; // Edited by Finn
long msgQueue = 0;
};

45 changes: 45 additions & 0 deletions src/F01Handler.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
/*
* F01Handler.cpp
*
* Created on: 12 june 2024
* Author: Finn Roters
*/

#include "F01Handler.h"

static F01Handler *instance; // defines a static pointer to an "F01Handler" instance (ensures that there is only one instance of the class).


// Check whether instance points to nullptr (i.e. no valid memory area) (if yes, a new instance of F01Handler is created).
F01Handler *F01Handler::getInstance()
{
if (!instance)
{
instance = new F01Handler();
};
return instance;
};

// Constructor of the F01Handler class (empty, because no special initialisations are necessary).
F01Handler::F01Handler()
{
}


int F01Handler::execute(Command *command)
{
//int duration = command->getT();
int valvePin = 10; // Pin for the water valve.
Serial.println("F01 command has started");
// Open the water valve
PinControl::getInstance()->writeValue(valvePin, 1, 0); // Set the pin of the water valve to high (0 = digital).

// Wait for the specified duration
//delay(duration);
delay(command->getT());

// Close the water valve
PinControl::getInstance()->writeValue(valvePin, 0, 0); // Set the pin of the water valve to low (0 = digital).
Serial.println("F01 command is done");
return 0;
}
28 changes: 28 additions & 0 deletions src/F01Handler.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
/*
* F01Handler.h
*
* Created on: 12 june 2024
* Author: Finn Roters
*/

#ifndef F01HANDLER_H_
#define F01HANDLER_H_
#include "GCodeHandler.h"
#include "Config.h"
#include "CurrentState.h"
#include "pins.h"
#include "PinControl.h"

class F01Handler : public GCodeHandler // Class F01Handler is defined, which inherits from GCodeHandler.
{
public: // can be called from outside.
static F01Handler *getInstance(); // static method that returns an instance of the "F01Handler" class.
int execute(Command *); // method is used to execute the G- and F-code.

private: // only accessible within the "F01Handler" class
F01Handler(); // private constructor of the class (prevents objects of the class from being created directly).
F01Handler(F01Handler const &); // private copy constructor (This prevents the class from being copied).
void operator=(F01Handler const &); // private assignment operator (This prevents objects from being assigned to the class).
};

#endif /* F01HANDLER_H_ */
63 changes: 63 additions & 0 deletions src/F02Handler.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,63 @@
/*
* F02Handler.cpp
*
* Created on: 1 july 2024
* Author: Finn Roters
*/

#include "F02Handler.h"

static F02Handler *instance; // defines a static pointer to an "F02Handler" instance (ensures that there is only one instance of the class).

unsigned int F02Handler::pulse;
float F02Handler::totalMilliLiters;
const float F02Handler::conversionFactor = 1.96; // The irrigation system dispenses 42.64 ml per second and 21.79 pulses per second are measured. If 42.64 ml is divided by 21.79 pulses, the result is 1.96 ml per pulse.
const float F02Handler::offset = 18.75; // The milliliter output per second is not linear, but can be described by the polynomial 42.64 ml * t + 18.75 ml. The offset is 18.75 ml.
// Check whether instance points to nullptr (i.e. no valid memory area) (if yes, a new instance of F02Handler is created).
F02Handler *F02Handler::getInstance()
{
if (!instance)
{
instance = new F02Handler();
};
return instance;
};

// Constructor of the F42Handler class (empty, because no special initialisations are necessary).
F02Handler::F02Handler()
{
}


int F02Handler::execute(Command *command)
{
unsigned int valvePin = 10; // Pin for the water valve.
unsigned int sensorPin = 2; // Pin 2 (Arduino Mega 2560) Interrupt capable
pulse = 0;
totalMilliLiters = 0.0;
pinMode(sensorPin, INPUT);
attachInterrupt(digitalPinToInterrupt(sensorPin), F02Handler::pulseCount, RISING);

Serial.println("F02 command has started");
// Open the water valve
PinControl::getInstance()->writeValue(valvePin, 1, 0); // Set the pin of the water valve to high (0 = digital).

Serial.print("command->getN(): ");
Serial.println(command->getN()); // Output of the value of command->getN()

while(totalMilliLiters < command->getN()){
Serial.print("Pulse : ");
Serial.println(pulse);
Serial.print("Total Ml : ");
Serial.println(totalMilliLiters);
}
// Close the water valve
PinControl::getInstance()->writeValue(valvePin, 0, 0); // Set the pin of the water valve to low (0 = digital).
Serial.println("F02 is done");
return 0;
}

void F02Handler::pulseCount() {
pulse++;
totalMilliLiters = pulse * conversionFactor + offset;
}
34 changes: 34 additions & 0 deletions src/F02Handler.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
/*
* F02Handler.h
*
* Created on: 1 july 2024
* Author: Finn Roters
*/

#ifndef F02HANDLER_H_
#define F02HANDLER_H_
#include "GCodeHandler.h"
#include "Config.h"
#include "CurrentState.h"
#include "pins.h"
#include "PinControl.h"

class F02Handler : public GCodeHandler // Class F02Handler is defined, which inherits from GCodeHandler.
{
public: // can be called from outside.
static F02Handler *getInstance(); // static method that returns an instance of the "F02Handler" class.
int execute(Command *); // method is used to execute the G- and F-code.

private: // only accessible within the "F02Handler" class
F02Handler(); // private constructor of the class (prevents objects of the class from being created directly).
F02Handler(F02Handler const &); // private copy constructor (This prevents the class from being copied).
void operator=(F02Handler const &); // private assignment operator (This prevents objects from being assigned to the class).
static void pulseCount(); // Function pulseCount is declared statically in order to exist during the entire runtime of the programme and only be valid in this area.
static unsigned int pulse;
static float totalMilliLiters;
static const float conversionFactor;
static const float offset;
};

#endif /* F02HANDLER_H_ */

2 changes: 1 addition & 1 deletion src/F21Handler.cpp
Original file line number Diff line number Diff line change
@@ -24,7 +24,7 @@ F21Handler::F21Handler()

int F21Handler::execute(Command *command)
{

ParameterList::getInstance()->readValue(command->getP());

return 0;
12 changes: 12 additions & 0 deletions src/GCodeProcessor.cpp
Original file line number Diff line number Diff line change
@@ -232,6 +232,18 @@ GCodeHandler *GCodeProcessor::getGCodeHandler(CommandCodeEnum codeEnum)
handler = G28Handler::getInstance();
}

// Edited by Finn:
if (codeEnum == F01)
{
handler = F01Handler::getInstance();
}

// Edited by Finn:
if (codeEnum == F02)
{
handler = F02Handler::getInstance();
}

if (codeEnum == F09)
{
handler = F09Handler::getInstance();
3 changes: 3 additions & 0 deletions src/GCodeProcessor.h
Original file line number Diff line number Diff line change
@@ -17,6 +17,9 @@
#include "G00Handler.h"
#include "G28Handler.h"

#include "F01Handler.h" // Edited by Finn
#include "F02Handler.h" // Edited by Finn

#include "F09Handler.h"

#include "F11Handler.h"
6 changes: 3 additions & 3 deletions src/src.ino
Original file line number Diff line number Diff line change
@@ -3,7 +3,6 @@
Created: 11/14/2019 9:51:10 PM
Author: Tim Evers
*/

#include "TMC2130_Basics.h"
#include "farmbot_arduino_controller.h"
//#include <SPI.h>
@@ -14,7 +13,8 @@
// the setup function runs once when you press reset or power the board
void setup()
{
startSerial();
Serial.begin(9600);
//startSerial();
setPinInputOutput();

readParameters();
@@ -56,5 +56,5 @@ void loop()
checkEmergencyStop();
checkParamsChanged();
periodicChecksAndReport();

}