use 5kHz as pwm frequency for motors

So we don't get the motors stopping to turn when changing direction at high speeds because of current limit on the vnh7070
pull/1/head
EmaMaker 2020-12-16 19:21:52 +01:00
parent 5566afb5bc
commit b9eefb2c10
1 changed files with 7 additions and 4 deletions

View File

@ -11,6 +11,7 @@ Motor::Motor(int a, int b, int pwm, int angle_){
pinMode(pinA, OUTPUT);
pinMode(pinB, OUTPUT);
pinMode(pinPwm, OUTPUT);
analogWriteFrequency(pinPwm, 5000);
}
Motor::Motor(){ }
@ -38,12 +39,14 @@ void Motor::drive(int speed){
}
void Motor::test(){
digitalWrite(pinA, 1);
digitalWrite(pinB, 0);
analogWrite(pinPwm, 255);
delay(1500);
digitalWrite(pinA, 0);
digitalWrite(pinB, 1);
analogWrite(pinPwm, 255);
delay(1500);
digitalWrite(pinA, 1);
digitalWrite(pinB, 0);
analogWrite(pinPwm, 255);
delay(1500);
}