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 vnh7070docs
parent
5566afb5bc
commit
b9eefb2c10
|
@ -11,6 +11,7 @@ Motor::Motor(int a, int b, int pwm, int angle_){
|
||||||
pinMode(pinA, OUTPUT);
|
pinMode(pinA, OUTPUT);
|
||||||
pinMode(pinB, OUTPUT);
|
pinMode(pinB, OUTPUT);
|
||||||
pinMode(pinPwm, OUTPUT);
|
pinMode(pinPwm, OUTPUT);
|
||||||
|
analogWriteFrequency(pinPwm, 5000);
|
||||||
}
|
}
|
||||||
|
|
||||||
Motor::Motor(){ }
|
Motor::Motor(){ }
|
||||||
|
@ -38,12 +39,14 @@ void Motor::drive(int speed){
|
||||||
}
|
}
|
||||||
|
|
||||||
void Motor::test(){
|
void Motor::test(){
|
||||||
digitalWrite(pinA, 1);
|
|
||||||
digitalWrite(pinB, 0);
|
|
||||||
analogWrite(pinPwm, 255);
|
|
||||||
delay(1500);
|
|
||||||
digitalWrite(pinA, 0);
|
digitalWrite(pinA, 0);
|
||||||
digitalWrite(pinB, 1);
|
digitalWrite(pinB, 1);
|
||||||
analogWrite(pinPwm, 255);
|
analogWrite(pinPwm, 255);
|
||||||
delay(1500);
|
delay(1500);
|
||||||
|
|
||||||
|
digitalWrite(pinA, 1);
|
||||||
|
digitalWrite(pinB, 0);
|
||||||
|
analogWrite(pinPwm, 255);
|
||||||
|
delay(1500);
|
||||||
|
|
||||||
}
|
}
|
Loading…
Reference in New Issue