opener-6

Dependencies:   TextLCD_HelloWorld2 TextLCD mbed

Fork of TextLCD_HelloWorld2 by Wim Huiskamp

main.cpp

Committer:
Martin1000
Date:
2018-04-16
Revision:
5:93f48c84e645
Parent:
4:a3e4bb2053cb

File content as of revision 5:93f48c84e645:


//  DOOR OPENER   version 1.4 (Opener-6)
//
//
//  program and related hardware serve to test the "door opener"
//  general function:
//
//      open and close via buttons or automatically
//      motor stops when endposition is reached (or current to high)
//      duty cycle, ramp- time and pause time for automatic
//      are adjustable via potentiometers
//
//      current, cycles, ramp- time, pause- time will be displayed
//
//
//
//  include the following functions:
//  read the digital inputs         button open
//                                  button close
//                                  proximity switch open
//                                  proximity switch close
//                                  auto_on
//
//  read the analog inputs          motor_current
//                                  duty_cycle      10..100%
//                                  ramp_time       0.1...9.9 sec
//                                  pause_time      1.0..99.9 sec
//
//  set the outputs                 myled
//                                  out_status_led
//                                  out_led_open
//                                  out_led_close
//                                  pwm_close
//                                  pwm_open
//                                  motor enable
//  ---------------------------------------------
//  first date  : 26-07-2017
//  last change : 10-11-2017
//  name        : Hillebrand, Martin (Iserlohn)
//  target      : FRDM K64F (from NXP)
//  software    : mbed (online)
//  programming : USB direct to SDA- interface
//  ---------------------------------------------

#include "mbed.h"
#include "TextLCD.h"

#define     OPEN        1
#define     CLOSE       2

// variable declaration
// ====================

int     old_value           = 0;    //         for single shot putty- output
int     new_value           = 0;    //         dto.

float   duty_open           = 0;    //         duty cycle in direction open
float   duty_close          = 0;    //         duty cycle in direction close

double  motor_current       = 0;    //         current from motor controller CT

int     button_open         = 0;    //         following variables contains the 
int     button_close        = 0;    //         input values, but logical correct
int     endpos_open         = 0;    //         e. g.  button_open = 1 activ
int     endpos_close        = 0;    //         switch_auto = 1, when auto is ON
int     switch_auto         = 0;    //         
int     time_flag           = 0;    //         flag for resetting timer

int     dir                 = 0;
int     off_flag            = 0;
int     auto_status         = 0;
int     auto_cycle          = 0;
int     k                   = 0;
int     start_move          = 0;
int     flag_9              = 0;



float   current_motor       = 0;    //          
double  duty_cycle_percent  = 0;    //                     
double  duty_cycle_current  = 0;    //         

double  pause_time          = 0;    //          
double  ramp_time           = 0;
double  voltage3v3          = 0;    //          analog values refer  
double  m_old_value         = 0;
double  m_new_value         = 0;
double  elapsed_time        = 0;    // elapsed time since t.start()
double  timeout_x_time      = 0;    // elapsed time for timeout
double  gradient            = 0;    // gradient for solving
double  timeouttime         = 60;   // fix value for reaching the endposition


Timer   t;   
Timer   x;

// function declaration
// ====================

void    initialize(void);
void    state_to_usb(void);
void    read_inputs(void);
void    monitor_output(void);
void    endpos_led(void);
void    motor_manual(int);
void    motor_auto(int);
void    automatic(void);
void    motor_off(void);
void    motor_off_auto(void);

void    manual_mode(void);
void    lcd_output_start(void);     // display after reset
void    lcd_output_setting(void);     // setting mode
void    lcd_output_manual(void);     // auto, waiting for close door
void    lcd_output_auto0(void);     // auto, close, waiting for start
void    lcd_output_auto1(void);     // 
void    lcd_output_auto2(void);
void    lcd_output_auto3(void);


// define inputs and outputs
// =========================

DigitalOut myled(LED1);             // internal Test- LED
PwmOut     pwm_open(PTD2);          // PWM- signal for direction open
PwmOut     pwm_close(PTD0);         // PWM- signal for direction close

DigitalOut out_enable(PTC4);         // enable motor driver
DigitalOut out_led_open(PTC16);      // indicator in button open
DigitalOut out_led_close(PTC17);     // indicator in button close
DigitalOut out_led_status(PTB9);     // led status
 
DigitalIn  in_btn_open(PTD1);       // button open
DigitalIn  in_btn_close(PTD3);      // button close
DigitalIn  in_end_pos_open(PTB23);  // signal endposition open
DigitalIn  in_end_pos_close(PTA1);  // signal endposition close
DigitalIn  in_sw_auto(PTC12);       // switch to start auto sequence


AnalogIn    a_in_motor(PTC10);      // A5- motor current
AnalogIn    a_in_duty(PTC11);       // A4- duty cycle analog 
AnalogIn    a_in_ramp(PTB11);       // A3- ramp analog value 0.1..9.9  seconds
AnalogIn    a_in_pause(PTB10);      // A2- pause analog value0.0..99.9 seconds
AnalogIn    a_in_3v3(PTB3);         // A1- reference voltage 3,3 volt



/*
AnalogIn    a_in_motor(PTB2);       // A0- motor current
AnalogIn    a_in_duty(PTB3);        // A1- duty cycle analog 
AnalogIn    a_in_ramp(PTB10);       // A2- ramp analog value 0.1..9.9  seconds
AnalogIn    a_in_pause(PTB11);      // A3- pause analog value0.0..99.9 seconds
AnalogIn    a_in_3v3(PTC11);        // A4- reference voltage 3,3 volt

*/
Serial pc(USBTX, USBRX);            //  Host PC Communication channels tx, rx
I2C i2c_lcd(PTE25,PTE24);           // SDA, SCL for K64

TextLCD_I2C lcd(&i2c_lcd, 0x27<<1, TextLCD::LCD20x4);  

//-----------------------------------------------------------------------------
void    lcd_output_start(void)
{
    wait(0.5);
    lcd.setBacklight(TextLCD::LightOn);     // LCD backlight on
    lcd.cls();
    lcd.printf("- door opener v4.6 -");   // LCD Headline
}
//-----------------------------------------------------------------------------
void    lcd_output_setting(void)
{
    lcd.locate(0,0);                        
    lcd.printf("--- setting mode ---");
    lcd.locate(0,1);                        
    lcd.printf("duty cycle =  %3.0f %% ",duty_cycle_percent);
    lcd.locate(0,2);                        
    lcd.printf("ramp time  =  %3.1f s ",ramp_time);
    lcd.locate(0,3);  
    if (pause_time >=10.0)
    {                                  
        lcd.printf("pause time = %3.1f s ",pause_time);
    }
    else
    {
        lcd.printf("pause time =  %3.1f s ",pause_time);
    }
}
//-----------------------------------------------------------------------------
void    lcd_output_manual(void)
{
   
    if (button_open || button_close)
    {
        k++;
        if (k >8)
        {
            lcd.cls();
            lcd.locate(0,0);               
            lcd.printf("--- manuel mode ---\n");
            motor_current = (double)a_in_motor*1000.0;
            lcd.locate(0,2);               
            lcd.printf("Current = %6.1f mA\n",motor_current);
            lcd.locate(0,3);               
            lcd.printf("duty    = %5.0f %%\n",duty_cycle_current);
            k = 0;
        }
    }
}
//-----------------------------------------------------------------------------
void    lcd_output_auto0(void)
{
    k++;
    if (k >8)
    {
        
    lcd.cls();
    lcd.locate(0,0);  
    lcd.printf("-- automatic mode --\n");
    lcd.locate(0,1);  
    lcd.printf("status = %d\n", auto_status);
    motor_current = (double)a_in_motor*1000.0;
    lcd.locate(0,2);  
    lcd.printf("door is open");
    lcd.locate(0,3);  
    lcd.printf("close door!\n");
    k = 0;
    }
}
//-----------------------------------------------------------------------------
void    lcd_output_auto1(void)
{
    k++;
    if (k >8)
    {
        
    lcd.cls();
    lcd.locate(0,0);  
    lcd.printf("-- automatic mode --\n");
    lcd.locate(0,1);  
    lcd.printf("status = %d\n", auto_status);
    motor_current = (double)a_in_motor*1000.0;
    lcd.locate(0,2);  
    lcd.printf("door is closed");
    lcd.locate(0,3);  
    lcd.printf("waiting for start!   ");
    k = 0;
    }
}


//-----------------------------------------------------------------------------
void    lcd_output_auto2(void)
{
    
    k++;
    if (k >8)
    {
        
    lcd.cls();
    lcd.locate(0,0);  
    lcd.printf("-- automatic mode --\n");
    lcd.locate(0,1);  
    if (dir == OPEN)
    {
        lcd.printf("status = %d OPEN \n", auto_status);
    }
    if (dir == CLOSE)
    {
        lcd.printf("status = %d CLOSE\n", auto_status);
    }
    motor_current = (double)a_in_motor*1000.0;
    lcd.locate(0,2);  
    lcd.printf("running, cycle %d    ",auto_cycle);

    lcd.locate(0,3);  
    lcd.printf("Current = %6.1f mA\r\n",motor_current);
    k = 0;
    }
}


//-----------------------------------------------------------------------------
void    lcd_output_auto3(void)
{
    k++;
    if (k >8)
    {
        
    lcd.cls();
    lcd.locate(0,0);  
    lcd.printf("-- automatic mode --\n");
    lcd.locate(0,1);  
    lcd.printf("status = %d\n", auto_status);
    motor_current = (double)a_in_motor*1000.0;
    lcd.locate(0,2);  
    lcd.printf("running, cycle %d\r\n",auto_cycle);

    lcd.locate(0,3);  
    lcd.printf("Pause: %3.1f of %3.1f s\r\n",elapsed_time, pause_time);
    k = 0;
    }
}

//-----------------------------------------------------------------------------
void    monitor_output(void)
{
    m_old_value = duty_cycle_percent + ramp_time + pause_time;
    
    if (abs(m_new_value - m_old_value) > 1.0)
    {
        pc.printf("\r\n");
        pc.printf("----------------------------\r\n");
        pc.printf("duty  cycle = %3.1f Prozent \r\n", duty_cycle_percent);
        pc.printf("ramp  time  = %3.1f Sekunden \r\n", ramp_time);
        pc.printf("pause time = %4.1f  Sekunden \r\n",  pause_time);
        wait(0.1);
    }
    m_new_value = m_old_value;
}
//-----------------------------------------------------------------------------
void    read_inputs(void)           // and calculate 
{
    button_open         =   !in_btn_open;               
    button_close        =   !in_btn_close;
    
    endpos_open         =   !in_end_pos_open; 
    endpos_close        =   !in_end_pos_close;
    switch_auto         =   !in_sw_auto;
    
    
    
    voltage3v3          =   (float)a_in_3v3;
    
    duty_cycle_percent  =   (double)(a_in_duty*100.0f/voltage3v3);
    if (duty_cycle_percent > 100.0)  duty_cycle_percent = 100.0;
    if (duty_cycle_percent < 10.0)   duty_cycle_percent =  10.0;
    
    ramp_time           =   (double)(a_in_ramp*9.9f/voltage3v3);
    if (ramp_time <0.1) ramp_time = 0.1;
    if (ramp_time >9.9) ramp_time = 9.9;
      
    pause_time          =   (double)(a_in_pause*99.9f/voltage3v3);
    if (pause_time <1.0)  pause_time = 1.0;
    if (pause_time >99.9) pause_time = 99.9;
    
    if (!button_open && !button_close && !switch_auto)
    {
        lcd_output_setting();
    }
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
void    initialize(void)
{
    out_led_status = 1;
    out_enable = 1;
    pwm_close.period(1.0/1000);
    pwm_open.period(1.0/1000);
}
// -----------------------------------------------------------------------------
void    endpos_led(void)
{
        if (endpos_open) // switching ON of the "end pos"-led in the button OPEN
        {                   
            out_led_open = 1;
        } else 
        {                
            out_led_open = 0;
        }
        //=====================================================================
        if (endpos_close) // switching ON "end pos"-led in the button CLOSE
        {                                       
            out_led_close = 1;
        } else
        {
            out_led_close = 0;
        }
}
// ----------------------------------------------------------------------------
void    state_to_usb(void)
{
    new_value = (int)(button_open * 1 + button_close * 2 + endpos_open * 
    4 + endpos_close * 8 + switch_auto * 16 + auto_status *32);
    
    if (new_value!= old_value) 
    {           // state of inputs if new values different from former values

        pc.printf("----------------------\r\n");
        pc.printf("Button Open          %d \r\n", (int)button_open);
        pc.printf("Button Close         %d \r\n", (int)button_close);
        pc.printf("End Position Open    %d \r\n", (int)endpos_open);
        pc.printf("End Position Close   %d \r\n", (int)endpos_close);
        pc.printf("Switch Auto          %d \r\n", (int)switch_auto);
        pc.printf("auto status          %d \r\n", (int)auto_status);
        

        old_value = new_value;              
    }
    out_led_status = !out_led_status;       
    wait(0.05);
}
// -----------------------------------------------------------------------------
void    automatic(void)
{
        switch (auto_status) 
        {
// -----------------------------------------------------------------------------            
            case 0:
                lcd_output_auto0();
                if (endpos_close)
                {
                    auto_status = 1;
                }                 
            break;
// -----------------------------------------------------------------------------            
            case 1:
                lcd_output_auto1();
                if (endpos_close && button_open)
                {
                    auto_status = 2;        // forward to status 2
                }   
                if (!endpos_close)          // back to status 0
                {
                    auto_status = 0;
                }   
            break;
// -----------------------------------------------------------------------------            
            case 2:
                lcd_output_auto1();
                if (endpos_close && !button_open)  // release start button
                {
                    auto_status = 3;
                }    
                if (!endpos_close)                  // back to status 0
                {
                    auto_status = 0;
                }   
            break;
// -----------------------------------------------------------------------------            
            case 3:
                lcd_output_auto2();
                if (endpos_close && !button_open)   // release start button
                {
                    wait(0.3);
                    auto_status = 4;
                    start_move  = 1;        //?
                    time_flag   = 0;
                }    
            break;
// -----------------------------------------------------------------------------            
            case 4:
                lcd_output_auto2();
                motor_auto(OPEN);    // motor runs until 
                                     // a.) position is open      
                                     // b.) auto switch turned off 
                                     // c.) timeout reached
                                     //    
                start_move = 0;
                if (!endpos_close)   // motor leave endpos close
                {
                    x.reset();
                    x.start();
                    timeout_x_time = 0;
                    
                    auto_status = 5;
                    
                }    
            break;
// -----------------------------------------------------------------------------        
        case 5:
                lcd_output_auto2();
                motor_auto(OPEN);     // motor runs until 
                                      // a.) position is open      
                                      // b.) auto switch turned off 
                                      // c.) timeout reached
                                      //  
                    
                timeout_x_time  = x.read();                
                if (timeout_x_time > timeouttime)
                {
                    motor_off_auto();
                    out_led_status = 1;
                    
                }
        
            
            
            
                
                    
                if (endpos_open)      // motor reach open position
                {
                    motor_off_auto();
                    auto_status = 6;
                }    
        break;
// -----------------------------------------------------------------------------        
        case 6:
                lcd_output_auto2();
                time_flag   = 0;
                if (endpos_open)        //
                {
                    auto_status = 7;
                }    
        break;              
// -----------------------------------------------------------------------------        
        case 7:
                lcd_output_auto3();
                if (!time_flag)
                {
                    t.reset();
                    t.start();
                    time_flag = 1;
                    elapsed_time = 0;
                }
                elapsed_time = t.read();                
                if (elapsed_time > pause_time)
                {
                    auto_status = 8;
                    time_flag = 0;
                }
        break;
// -----------------------------------------------------------------------------        
            case 8:
                lcd_output_auto2();
                motor_auto(CLOSE);    // motor runs until 
                                     // a.) position is open      
                                     // b.) auto switch turned off 
                                     // c.) timeout reached
                if (!endpos_open)   
                {
                    auto_status = 9;
                }    
            break;
// -----------------------------------------------------------------------------        
        case 9:
                lcd_output_auto2();
                motor_auto(CLOSE);     // motor runs until 
                                      // a.) position is open      
                                      // b.) auto switch turned off 
                                      // c.) timeout reached
                if (endpos_close)   
                {
                    motor_off_auto();
                    auto_status = 10;
                    time_flag = 0;
                    auto_cycle++;                   
                    if (auto_cycle > 100000) auto_cycle = 0;
                }    
        break;
// -----------------------------------------------------------------------------        
        case 10:
                lcd_output_auto3();
                if (!time_flag)
                {
                    t.reset();
                    t.start();
                    time_flag = 1;
                    elapsed_time = 0;
                }
                elapsed_time = t.read();                
                if (elapsed_time > pause_time)
                {
                    auto_status = 11;
                    time_flag = 0;
                }
        break;
// -----------------------------------------------------------------------------        
        case 11:
                lcd_output_auto2();
                if (endpos_close)  
                {
                    auto_status = 2;
                }    
        break;
// -----------------------------------------------------------------------------        
        default:        
        break;
    }
}
// -----------------------------------------------------------------------------
void    motor_manual(int direction)
{
    if (!time_flag)
    {
        t.reset();
        t.start();
        time_flag = 1;
        elapsed_time = 0;
    }
    elapsed_time = t.read();
    gradient = (duty_cycle_percent-10.0f)/ramp_time;
    
    if (elapsed_time < ramp_time) 
    {
        duty_cycle_current = 10.0 + elapsed_time * gradient;
    }
    else
    {
        duty_cycle_current = duty_cycle_percent;
    }
    if (direction == OPEN)
    {
        pwm_open.write(duty_cycle_current/100.0f);
    }
    if (direction == CLOSE)
    {
        pwm_close.write(duty_cycle_current/100.0f);
    }
    lcd_output_manual();
}
// ----------------------------------------------------------------------------
void    motor_auto(int direction)
{
    dir = direction;
    
    if (!time_flag)
    {
        t.reset();
        t.start();
        time_flag = 1;
        elapsed_time = 0;
    }
        
    elapsed_time = t.read();
    gradient = (duty_cycle_percent-10.0f)/ramp_time;
    
    if (elapsed_time < ramp_time) 
    {
        duty_cycle_current = 10.0 + elapsed_time * gradient;
    }
    else
    {
        duty_cycle_current = duty_cycle_percent;
    }
    if (direction == OPEN)
    {
        pwm_open.write(duty_cycle_current/100.0f);
    }
    if (direction == CLOSE)
    {
        pwm_close.write(duty_cycle_current/100.0f);
    }
}
// ----------------------------------------------------------------------------
void    motor_off_auto(void)
{
    duty_cycle_current = 0;
    pwm_close.write(0);
    pwm_open.write(0);
}
// ----------------------------------------------------------------------------
void    motor_off(void)
{
    duty_cycle_current = 0;
    pwm_close.write(0);
    pwm_open.write(0);
    lcd_output_manual();
}
// ----------------------------------------------------------------------------
void    manual_mode(void)
{
    auto_status = 0;
    //-----------------------------------
    if(button_open && !endpos_open)     
    {
        motor_manual(OPEN);
        off_flag = 0;
    }    
    //-----------------------------------
    if(button_close && !endpos_close)     
    {
        motor_manual(CLOSE);
        off_flag = 0;
    }    
    //-----------------------------------
    if (off_flag)
    {
        motor_off();
        off_flag = 0;   
        time_flag = 0;
    }
}
// ----------------------------------------------------------------------------
// ----------------------------------------------------------------------------
// ----------------------------------------------------------------------------
int main()
{
    initialize();
    lcd_output_start();
    while (1) 
    {                                         
        read_inputs();
        state_to_usb();    
        monitor_output();
        endpos_led();

        off_flag = 1;               // to prevent display flicker

        if (!switch_auto)           // manual mode
        {
            manual_mode();
        }        
        if (switch_auto)            // auto mode
        {   
            automatic();
        }
    }
}