Skip to content

Commit

Permalink
fixed Bug
Browse files Browse the repository at this point in the history
  • Loading branch information
UlmerMan committed Feb 10, 2023
1 parent 99607ab commit 5b8b8a2
Show file tree
Hide file tree
Showing 5 changed files with 15 additions and 5 deletions.
1 change: 1 addition & 0 deletions AUTHORS
Original file line number Diff line number Diff line change
@@ -1 +1,2 @@
Manuel Ulmer
Marko Mojovic
2 changes: 1 addition & 1 deletion library.properties
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
name=Elegoo
version=1.1.0
version=1.2.0
author=Manuel Ulmer
url=https://git.aerospace-lab.de/manuel.ulmer/ELEGOO-Smart-Robot-Car-Kit
maintainer=Manuel Ulmer
Expand Down
3 changes: 2 additions & 1 deletion src/Elegoo.h
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,7 @@ class elegoo
void stop();
long getDistance();
long getDistance(int angle);
long getDistanceReturn(int angle);
void forwardT(int speed, float time);
void backT(int speed, float time);
void leftT(int speed, float time);
Expand All @@ -77,7 +78,7 @@ class elegoo
char getBTdec();
void delay(unsigned long time);
void remote();
float regler(float ist, float soll, int p_faktor);
float regler(float ist, float soll, int p_faktor, float d_faktor, float i_faktor);
void IRbegin();
void keepDistance();
void enableKeepDistance();
Expand Down
2 changes: 1 addition & 1 deletion src/Sensors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ long elegoo::getDistance(int angle) {
}

long elegoo::getDistanceReturn(int angle){

}

int elegoo::getLightR(){
Expand Down
12 changes: 10 additions & 2 deletions src/movement.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
#include "movement.h"

float i_val, lastDifference;

/*define forward function*/
void elegoo::forward(int speed){
analogWrite(ENA,speed);
Expand Down Expand Up @@ -83,8 +85,14 @@ void elegoo::rightT(int speed, float time){
}


float elegoo::regler(float ist, float soll, int p_faktor){
float elegoo::regler(float ist, float soll, int p_faktor, float d_faktor, float i_faktor){
float abweichung = soll - ist;
float ergebnis = (abweichung * p_faktor);

float d_val = abweichung - lastDifference;

float ergebnis = (abweichung * p_faktor) + (d_val * d_faktor)+(i_val*i_faktor);

lastDifference = abweichung;
i_val= i_val + lastDifference;
return ergebnis;
}

0 comments on commit 5b8b8a2

Please sign in to comment.