Am Model Funktionstuechtig

Motor ueber Sigma Delta Ansteuerung
Sanft in die Endschalter fahren
This commit is contained in:
Toberfra 2022-02-11 09:57:20 +01:00
parent 0971473518
commit a59f23bc5c
5 changed files with 69 additions and 43 deletions

View File

@ -62,27 +62,42 @@ void KlappenAblauf::fsmStep(){
switch (aktuellerState) switch (aktuellerState)
{ {
case INIT: case INIT:
aktuellerState = START_AUF; aktuellerState = REF_FAHRT;
setOpen(false); setOpen(false);
break; break;
case REF_FAHRT:
timer = 5000;
setSollSpeed(LANGSAMME_FAHRT);
aktuellerState = FAEHRT_AUF_LANGSAM;
break;
case WARTE_OFFEN: case WARTE_OFFEN:
case WARTE_GESCHLOSSEN: case WARTE_GESCHLOSSEN:
break; break;
case START_AUF: case START_AUF:
setSollSpeed(800); setSollSpeed(SCHNELLE_FAHRT);
timer = 5000; timer = 1800;
aktuellerState = FAEHRT_AUF; aktuellerState = FAEHRT_AUF_SCHNELL;
break; break;
case START_ZU: case START_ZU:
setSollSpeed(-1023); setSollSpeed(-SCHNELLE_FAHRT);
timer = 5000; timer = 1800;
aktuellerState = FAEHRT_ZU; aktuellerState = FAEHRT_ZU_SCHNELL;
break; break;
case FAEHRT_AUF: case FAEHRT_AUF_SCHNELL:
timer -= getDeltamsec();
if(timer <= 0){
timer = 2000;
setSollSpeed(LANGSAMME_FAHRT);
aktuellerState = FAEHRT_AUF_LANGSAM;
}
break;
case FAEHRT_AUF_LANGSAM:
timer -= getDeltamsec(); timer -= getDeltamsec();
if(timer <= 0){ if(timer <= 0){
setSollSpeed(0); setSollSpeed(0);
@ -90,7 +105,16 @@ void KlappenAblauf::fsmStep(){
} }
break; break;
case FAEHRT_ZU: case FAEHRT_ZU_SCHNELL:
timer -= getDeltamsec();
if(timer <= 0){
timer = 2000;
setSollSpeed(-LANGSAMME_FAHRT);
aktuellerState = FAEHRT_ZU_LANGSAM;
}
break;
case FAEHRT_ZU_LANGSAM:
timer -= getDeltamsec(); timer -= getDeltamsec();
if(timer <= 0){ if(timer <= 0){
setSollSpeed(0); setSollSpeed(0);

View File

@ -58,14 +58,17 @@ private:
void openSpeicherAbfrage(); void openSpeicherAbfrage();
typedef enum fsmStatesEnum{ typedef enum fsmStatesEnum{
INIT, INIT,
REF_FAHRT,
WARTE_OFFEN, WARTE_OFFEN,
START_ZU, START_ZU,
FAEHRT_ZU, FAEHRT_ZU_SCHNELL,
FAEHRT_ZU_LANGSAM,
WARTE_GESCHLOSSEN, WARTE_GESCHLOSSEN,
START_AUF, START_AUF,
FAEHRT_AUF, FAEHRT_AUF_SCHNELL,
FAEHRT_AUF_LANGSAM,
}fsmStates; }fsmStates;

View File

@ -21,7 +21,8 @@ void Motor::setMotorPwmPin(uint8_t pinPwm){
void Motor::setup(){ void Motor::setup(){
ArduinoAnpassung::setup(); ArduinoAnpassung::setup();
Timer1.initialize(100); //10kHz Timer1.initialize(100); //10kHz
Timer1.pwm(pinPwm , 0); pinMode(pinPwm , OUTPUT);
digitalWrite(pinPwm , 1);
Timer1.attachInterrupt(Motor::interruptEinsprung); Timer1.attachInterrupt(Motor::interruptEinsprung);
} }
@ -48,7 +49,27 @@ void Motor::interruptBerechnungen(){
setIstSpeed(istSpeed); setIstSpeed(istSpeed);
}*/ }*/
setIstSpeed(sollSpeed); istSpeed = sollSpeed;
summeSpeed += istSpeed;
if(summeSpeed >= 256)
{
summeSpeed -= 256;
digitalWrite(pinA , 1);
digitalWrite(pinB , 0);
}else if (summeSpeed <= -256){
summeSpeed += 256;
digitalWrite(pinA , 0);
digitalWrite(pinB , 1);
}else{
digitalWrite(pinA , 0);
digitalWrite(pinB , 0);
}
} }
@ -59,38 +80,14 @@ void Motor::interruptBerechnungen(){
void Motor::setSollSpeed(int16_t speed){ void Motor::setSollSpeed(int16_t speed){
/* if(speed >1023) if(speed > 256)
speed = 1023; speed = 256;
if(speed < -1023) if(speed < -256)
speed = -1023; */ speed = -256;
sollSpeed = speed; 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);
}

View File

@ -24,7 +24,7 @@ public:
protected: protected:
void setIstSpeed(int16_t speed);
static uint8_t pinPwm; static uint8_t pinPwm;
@ -42,7 +42,7 @@ protected:
int16_t sollSpeed; int16_t sollSpeed;
int16_t istSpeed; int16_t istSpeed;
//int16_t summeSpeed; int16_t summeSpeed;
bool richtung; bool richtung;
int16_t test; int16_t test;

View File

@ -31,6 +31,8 @@
#define TASTER_AUF 11 #define TASTER_AUF 11
#define TASTER_ZU 12 #define TASTER_ZU 12
#define SCHNELLE_FAHRT (256)
#define LANGSAMME_FAHRT (150)