PWM am Enable Pin

This commit is contained in:
Toberfra 2022-02-11 09:06:23 +01:00
parent 7cc556b1d6
commit 0971473518
3 changed files with 86 additions and 36 deletions

View File

@ -71,13 +71,13 @@ void KlappenAblauf::fsmStep(){
break; break;
case START_AUF: case START_AUF:
setMotorAktion(1); setSollSpeed(800);
timer = 5000; timer = 5000;
aktuellerState = FAEHRT_AUF; aktuellerState = FAEHRT_AUF;
break; break;
case START_ZU: case START_ZU:
setMotorAktion(-1); setSollSpeed(-1023);
timer = 5000; timer = 5000;
aktuellerState = FAEHRT_ZU; aktuellerState = FAEHRT_ZU;
break; break;
@ -85,7 +85,7 @@ void KlappenAblauf::fsmStep(){
case FAEHRT_AUF: case FAEHRT_AUF:
timer -= getDeltamsec(); timer -= getDeltamsec();
if(timer <= 0){ if(timer <= 0){
setMotorAktion(0); setSollSpeed(0);
aktuellerState = WARTE_OFFEN; aktuellerState = WARTE_OFFEN;
} }
break; break;
@ -93,7 +93,7 @@ void KlappenAblauf::fsmStep(){
case FAEHRT_ZU: case FAEHRT_ZU:
timer -= getDeltamsec(); timer -= getDeltamsec();
if(timer <= 0){ if(timer <= 0){
setMotorAktion(0); setSollSpeed(0);
aktuellerState = WARTE_GESCHLOSSEN; aktuellerState = WARTE_GESCHLOSSEN;
} }
break; break;

View File

@ -17,12 +17,84 @@ void Motor::setMotorPwmPin(uint8_t pinPwm){
} }
void Motor::setup(){ void Motor::setup(){
ArduinoAnpassung::setup(); ArduinoAnpassung::setup();
pinMode(pinPwm , OUTPUT); Timer1.initialize(100); //10kHz
digitalWrite(pinPwm , 1); Timer1.pwm(pinPwm , 0);
Timer1.attachInterrupt(Motor::interruptEinsprung);
} }
void Motor::interruptEinsprung(){
MyList *zeiger;
zeiger = ArduinoAnpassung::getErstesElement();
while(zeiger){
((Motor*)zeiger)->memberInterruptEinsprung();
zeiger = zeiger->getNachfolgerElement();
}
}
void Motor::memberInterruptEinsprung(){
interruptBerechnungen();
}
void Motor::interruptBerechnungen(){
/*if(sollSpeed > istSpeed){
istSpeed++;
setIstSpeed(istSpeed);
}
if(sollSpeed < istSpeed){
istSpeed --;
setIstSpeed(istSpeed);
}*/
setIstSpeed(sollSpeed);
}
void Motor::setSollSpeed(int16_t speed){
/* if(speed >1023)
speed = 1023;
if(speed < -1023)
speed = -1023; */
sollSpeed = speed;
}
void Motor::setIstSpeed(int16_t speed){
uint16_t pwm;
if(speed > 0)
{
pwm = speed ;
digitalWrite(pinA , 1);
digitalWrite(pinB , 0);
}else if (speed < 0){
pwm = -speed ;
digitalWrite(pinA , 0);
digitalWrite(pinB , 1);
}else{
pwm = 1023;
digitalWrite(pinA , 0);
digitalWrite(pinB , 0);
}
Timer1.pwm(Motor::pinPwm, pwm);
}
void Motor::memberSetup(){ void Motor::memberSetup(){
@ -34,30 +106,6 @@ void Motor::memberSetup(){
} }
void Motor::setMotorAktion(int8_t richtung){
if(richtung > 0){
digitalWrite( pinA , 1);
digitalWrite( pinB , 0);
digitalWrite(LED_BUILTIN , 1);
}else if(richtung < 0){
digitalWrite( pinA , 0);
digitalWrite( pinB , 1);
digitalWrite(LED_BUILTIN , 1);
}else{
digitalWrite( pinA , 0);
digitalWrite( pinB , 0);
digitalWrite(LED_BUILTIN , 0);
}
}
void Motor::setMotorAktion(int8_t richtung , int id ){
Motor *zeiger;
zeiger = (Motor*) searchIdElement(id);
if(zeiger)
zeiger->setMotorAktion(richtung);
}

View File

@ -16,22 +16,23 @@ public:
void setMotorPins(uint8_t pinA , uint8_t pinB); void setMotorPins(uint8_t pinA , uint8_t pinB);
static void setMotorPwmPin(uint8_t pinPwm); static void setMotorPwmPin(uint8_t pinPwm);
void setMotorAktion(int8_t richtung); void setSollSpeed(int16_t speed);
static void setMotorAktion(int8_t richtung , int id);
protected: protected:
void setIstSpeed(int16_t speed);
static uint8_t pinPwm; static uint8_t pinPwm;
virtual void memberSetup(); virtual void memberSetup();
//static void interruptEinsprung(); static void interruptEinsprung();
//void memberInterruptEinsprung(); void memberInterruptEinsprung();
//void InterruptEinsprung(); //void InterruptEinsprung();
void interruptBerechnungen(); void interruptBerechnungen();
@ -40,7 +41,8 @@ protected:
uint16_t timer; uint16_t timer;
int16_t sollSpeed; int16_t sollSpeed;
int16_t summeSpeed; int16_t istSpeed;
//int16_t summeSpeed;
bool richtung; bool richtung;
int16_t test; int16_t test;