mirror of
https://github.com/kevinveenbirkenbach/arduino_motor_controll.git
synced 2024-11-23 11:21:03 +01:00
Motorsteurung optimiert
This commit is contained in:
parent
a3504c6627
commit
f050f5c5f2
17
Motor.cpp
17
Motor.cpp
@ -8,26 +8,39 @@ int Motor::getBackwardsValue(){
|
|||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
int Motor::getSpeed(int direction){
|
||||||
|
if(direction==LOW){
|
||||||
|
return 255-this->speedPwm;
|
||||||
|
}
|
||||||
|
return this->speedPwm;
|
||||||
|
}
|
||||||
|
|
||||||
Motor::Motor(int pwmPin, int directionPin,bool forwardValue, int speedPwm, int directionDelay){
|
Motor::Motor(int pwmPin, int directionPin,bool forwardValue, int speedPwm, int directionDelay){
|
||||||
this->pwmPin = pwmPin;
|
this->pwmPin = pwmPin;
|
||||||
this->directionPin = directionPin;
|
this->directionPin = directionPin;
|
||||||
this->forwardValue = forwardValue;
|
this->forwardValue = forwardValue;
|
||||||
this->speedPwm = speedPwm;
|
this->speedPwm = speedPwm;
|
||||||
this->directionDelay= directionDelay;
|
this->directionDelay= directionDelay;
|
||||||
|
|
||||||
|
//Pins auf Output setzen
|
||||||
|
pinMode(pwmPin, OUTPUT );
|
||||||
|
pinMode(directionPin, OUTPUT );
|
||||||
|
digitalWrite(pwmPin, LOW );
|
||||||
|
digitalWrite(directionPin, LOW );
|
||||||
}
|
}
|
||||||
|
|
||||||
void Motor::forward(){
|
void Motor::forward(){
|
||||||
//Motor vor Änderungen stoppen
|
//Motor vor Änderungen stoppen
|
||||||
this->stop();
|
this->stop();
|
||||||
digitalWrite(this->directionPin,this->forwardValue);
|
digitalWrite(this->directionPin,this->forwardValue);
|
||||||
analogWrite(this->pwmPin, this->speedPwm);
|
analogWrite(this->pwmPin, this->getSpeed(this->forwardValue));
|
||||||
}
|
}
|
||||||
|
|
||||||
void Motor::backward(){
|
void Motor::backward(){
|
||||||
//Motor vor Änderungen stoppen
|
//Motor vor Änderungen stoppen
|
||||||
this->stop();
|
this->stop();
|
||||||
digitalWrite(this->directionPin,this->getBackwardsValue());
|
digitalWrite(this->directionPin,this->getBackwardsValue());
|
||||||
analogWrite(this->pwmPin, this->speedPwm);
|
analogWrite(this->pwmPin, this->getSpeed(this->getBackwardsValue()));
|
||||||
}
|
}
|
||||||
|
|
||||||
void Motor::stop(){
|
void Motor::stop(){
|
||||||
|
4
Motor.h
4
Motor.h
@ -14,6 +14,10 @@ class Motor{
|
|||||||
int forwardValue;
|
int forwardValue;
|
||||||
int speedPwm;
|
int speedPwm;
|
||||||
int directionDelay;
|
int directionDelay;
|
||||||
|
|
||||||
|
//Liefert die PWM-Geschwindigkeit in Abhängigkeit von der Richtung zurück
|
||||||
|
int getSpeed(int direction);
|
||||||
|
|
||||||
//Liefert den Vorwärtswert;HIGH oder LOW zurück
|
//Liefert den Vorwärtswert;HIGH oder LOW zurück
|
||||||
int getBackwardsValue();
|
int getBackwardsValue();
|
||||||
public:
|
public:
|
||||||
|
Loading…
Reference in New Issue
Block a user