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;
|
||||
}
|
||||
|
||||
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){
|
||||
this->pwmPin = pwmPin;
|
||||
this->directionPin = directionPin;
|
||||
this->forwardValue = forwardValue;
|
||||
this->speedPwm = speedPwm;
|
||||
this->directionDelay= directionDelay;
|
||||
|
||||
//Pins auf Output setzen
|
||||
pinMode(pwmPin, OUTPUT );
|
||||
pinMode(directionPin, OUTPUT );
|
||||
digitalWrite(pwmPin, LOW );
|
||||
digitalWrite(directionPin, LOW );
|
||||
}
|
||||
|
||||
void Motor::forward(){
|
||||
//Motor vor Änderungen stoppen
|
||||
this->stop();
|
||||
digitalWrite(this->directionPin,this->forwardValue);
|
||||
analogWrite(this->pwmPin, this->speedPwm);
|
||||
analogWrite(this->pwmPin, this->getSpeed(this->forwardValue));
|
||||
}
|
||||
|
||||
void Motor::backward(){
|
||||
//Motor vor Änderungen stoppen
|
||||
this->stop();
|
||||
digitalWrite(this->directionPin,this->getBackwardsValue());
|
||||
analogWrite(this->pwmPin, this->speedPwm);
|
||||
analogWrite(this->pwmPin, this->getSpeed(this->getBackwardsValue()));
|
||||
}
|
||||
|
||||
void Motor::stop(){
|
||||
|
Loading…
Reference in New Issue
Block a user