mirror of
https://gitlab.com/fabinfra/fabhardware/absaugungsklappensteuerung.git
synced 2025-03-12 14:51:44 +01:00
PWM am Enable Pin
This commit is contained in:
parent
7cc556b1d6
commit
0971473518
@ -71,13 +71,13 @@ void KlappenAblauf::fsmStep(){
|
||||
break;
|
||||
|
||||
case START_AUF:
|
||||
setMotorAktion(1);
|
||||
setSollSpeed(800);
|
||||
timer = 5000;
|
||||
aktuellerState = FAEHRT_AUF;
|
||||
break;
|
||||
|
||||
case START_ZU:
|
||||
setMotorAktion(-1);
|
||||
setSollSpeed(-1023);
|
||||
timer = 5000;
|
||||
aktuellerState = FAEHRT_ZU;
|
||||
break;
|
||||
@ -85,7 +85,7 @@ void KlappenAblauf::fsmStep(){
|
||||
case FAEHRT_AUF:
|
||||
timer -= getDeltamsec();
|
||||
if(timer <= 0){
|
||||
setMotorAktion(0);
|
||||
setSollSpeed(0);
|
||||
aktuellerState = WARTE_OFFEN;
|
||||
}
|
||||
break;
|
||||
@ -93,7 +93,7 @@ void KlappenAblauf::fsmStep(){
|
||||
case FAEHRT_ZU:
|
||||
timer -= getDeltamsec();
|
||||
if(timer <= 0){
|
||||
setMotorAktion(0);
|
||||
setSollSpeed(0);
|
||||
aktuellerState = WARTE_GESCHLOSSEN;
|
||||
}
|
||||
break;
|
||||
|
@ -17,12 +17,84 @@ void Motor::setMotorPwmPin(uint8_t pinPwm){
|
||||
}
|
||||
|
||||
|
||||
|
||||
void Motor::setup(){
|
||||
ArduinoAnpassung::setup();
|
||||
pinMode(pinPwm , OUTPUT);
|
||||
digitalWrite(pinPwm , 1);
|
||||
Timer1.initialize(100); //10kHz
|
||||
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(){
|
||||
@ -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);
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
@ -16,22 +16,23 @@ public:
|
||||
|
||||
void setMotorPins(uint8_t pinA , uint8_t pinB);
|
||||
static void setMotorPwmPin(uint8_t pinPwm);
|
||||
void setMotorAktion(int8_t richtung);
|
||||
static void setMotorAktion(int8_t richtung , int id);
|
||||
void setSollSpeed(int16_t speed);
|
||||
|
||||
|
||||
|
||||
|
||||
protected:
|
||||
|
||||
|
||||
|
||||
void setIstSpeed(int16_t speed);
|
||||
static uint8_t pinPwm;
|
||||
|
||||
|
||||
virtual void memberSetup();
|
||||
|
||||
|
||||
//static void interruptEinsprung();
|
||||
//void memberInterruptEinsprung();
|
||||
static void interruptEinsprung();
|
||||
void memberInterruptEinsprung();
|
||||
//void InterruptEinsprung();
|
||||
|
||||
void interruptBerechnungen();
|
||||
@ -40,7 +41,8 @@ protected:
|
||||
uint16_t timer;
|
||||
|
||||
int16_t sollSpeed;
|
||||
int16_t summeSpeed;
|
||||
int16_t istSpeed;
|
||||
//int16_t summeSpeed;
|
||||
|
||||
bool richtung;
|
||||
int16_t test;
|
||||
|
Loading…
x
Reference in New Issue
Block a user