Tel: +5584 32153771 | Mail: isaacdiego@gmail.com, s.natansilva@gmail.com, rmteles@gmail.com, mfernandes@dca.ufrn.br

Sources and Designs

For more information about the plant implemented with these codes, visit the prototype section.

  1. MCM
  2. DAMs
  3. SGM

1. MCM

The MCM was implemented using the Intel DN2800MT Mini-ITX platform with the Linux operating system (distribution: Ubuntu 13.10) therefore, its source code is a C code:

MA's main source:

#include "comunicacao.h"

#include <time.h>
#include <math.h>
#include <pthread.h>
#include <semaphore.h>
#include <sys/time.h>

#define TEMPO_INTERRUPCAO_CLOCK 100 // 100ms 
#define TEMPO_INTERRUPCAO_COLETOR 1000 // us
#define ERRO_MEDIO 72 // Em media o erro no sleep da thread eh de 68us

#define PWM_DEVICE "/dev/ttyACM0"
#define ADC_DEVICE "/dev/ttyACM1"
#define PSOC_DEVICE "/dev/ttyACM2"

#define PASSO 0.1
#define g 9.98
#define VAZAO_MAX 0.000069
#define AREA_DUTO 0.000017813919 // Area da sessão transversal do duto de saida
#define AREA_TANQUE 0.0062072 // Area da sessão do tanque
#define NIVEL_MAXIMO 0.3

//Threads
double current_timestamp();
void *clock_funcao(void* rank);
void *coletor_funcao(void* rank);
void *produtor_funcao(void* rank);
double eqDiferencial(double vazao, double nivel, double alpha_saida);
double rungekutta(double alpha_entrada, double alpha_saida, double nivel);

//Variaveis
char c_pwm_recebido, c_adc_recebido;
pthread_mutex_t mutex_leitura;
sem_t sem_clock;

int pwm_handle;
int adc_handle;
int psoc_handle;

pthread_t thread_clock;
pthread_t thread_coletor;
pthread_t thread_produtor;
 
union Nivel_union{
  float f;
  char c[4];
};

int main(int argc,char** argv){
  pwm_handle = abrir_porta(PWM_DEVICE);
  adc_handle = abrir_porta(ADC_DEVICE);
  psoc_handle = abrir_porta(PSOC_DEVICE);
  
  if(pwm_handle == -1){
    printf("Ocorreu erro na abertura do dispositivo PWM\n");
    exit(-1);
    
  }else if(adc_handle == -1){
    printf("Ocorreu erro na abertura do dispositivo ADC\n");
    exit(-1);
    
  }else if(psoc_handle == -1){
    printf("Ocorreu erro na abertura da PSOC\n");
    exit(-1);
    
  }
  
  sem_init(&sem_clock, 0, 0);
  pthread_mutex_init(&mutex_leitura, NULL);
  
  pthread_attr_t attr_clock;
  struct sched_param param_clock;
  param_clock.sched_priority = 99;
  pthread_attr_init(&attr_clock);  
  pthread_attr_setschedparam(&attr_clock, &param_clock);
  pthread_create(&thread_clock, &attr_clock, clock_funcao, (void*)0);
  
  pthread_attr_t attr_coletor;
  struct sched_param param_coletor;
  param_coletor.sched_priority = 40;
  pthread_attr_init(&attr_coletor);  
  pthread_attr_setschedparam(&attr_coletor, &param_coletor);
  pthread_create(&thread_coletor, &attr_coletor, coletor_funcao, (void*)0);    
  
  pthread_attr_t attr_produtor;
  struct sched_param param_produtor;
  param_produtor.sched_priority = 40;
  pthread_attr_init(&attr_produtor);  
  pthread_attr_setschedparam(&attr_produtor, &param_produtor);
  pthread_create(&thread_produtor, &attr_produtor, produtor_funcao, (void*)0);   
  
  pthread_join(thread_clock, NULL);
  pthread_join(thread_coletor, NULL); 
  pthread_join(thread_produtor, NULL); 

  close(pwm_handle);
  close(adc_handle);
  close(psoc_handle);
  
  sem_destroy(&sem_clock);
  pthread_mutex_destroy(&mutex_leitura);

  return 0;
}

// Clock
void *clock_funcao(void* rank){
  int erro = 0;
  double t0, t1;
  
  while(1){
    t0 = current_timestamp();
    usleep(TEMPO_INTERRUPCAO_CLOCK * 1000 - (erro + ERRO_MEDIO));    
    t1 = current_timestamp(); 
    
    sem_post(&sem_clock); 
    erro = erro + (((t1 - t0) - TEMPO_INTERRUPCAO_CLOCK) * 1000.0); // t1 - t0 resultado em uma fracao contendo os microsegundos
  }
  return NULL;
}

double current_timestamp() {
  struct timeval te; 
  gettimeofday(&te, NULL);
  double milliseconds = te.tv_sec*1000LL + te.tv_usec/1000.0;
  return milliseconds;
}

// Coletor
void *coletor_funcao(void* rank){
  char c[100];
  int n_bytes_lidos = 0;
  
  while(1){
    usleep(TEMPO_INTERRUPCAO_COLETOR);
    n_bytes_lidos = ler(pwm_handle,c,100);
    if(n_bytes_lidos > 0){
      pthread_mutex_lock(&mutex_leitura);
      c_pwm_recebido = c[n_bytes_lidos - 1];
      pthread_mutex_unlock(&mutex_leitura);
    }  
    
    n_bytes_lidos = ler(adc_handle,c,100);
    if(n_bytes_lidos > 0){
      pthread_mutex_lock(&mutex_leitura);
      c_adc_recebido = c[n_bytes_lidos - 1];
      pthread_mutex_unlock(&mutex_leitura);
    }
  }
}

// Produtor
void *produtor_funcao(void* rank){
  float nivel;
  char nivel_enviar;
  double alpha_entrada = 0.5;
  double alpha_saida = 0.5;
  while(1){    
    sem_wait(&sem_clock);
    system("clear");
    
    pthread_mutex_lock(&mutex_leitura);
    alpha_entrada = ((int)c_pwm_recebido);
    alpha_saida = ((int)c_adc_recebido);
    pthread_mutex_unlock(&mutex_leitura);
    
    if(alpha_entrada < 0)
      alpha_entrada += 255;
    if(alpha_saida < 0)
      alpha_saida += 255;
      
    alpha_entrada = alpha_entrada / 255.0;
    alpha_saida = alpha_saida / 255.0;
    
    printf ("STRSD  v0.1\n"); 
    printf ("SIMULATION PARAMETERS:\n");
    printf ("\tTank Area : %lf m²\n", AREA_TANQUE );
    printf ("\tOutput duct area : %lf m²\n", AREA_DUTO );
    printf ("\tMax level : %.2lf m\n", NIVEL_MAXIMO);
    printf ("INTERNAL VARIABLES:\n");
    printf("\tInput  Alpha = %lf\n", alpha_entrada);
    printf("\tOutput Alpha = %lf\n", alpha_saida);
    
    nivel = rungekutta(alpha_entrada, alpha_saida, nivel);
    if(nivel > NIVEL_MAXIMO){
      nivel = NIVEL_MAXIMO;
    }else if(nivel < 0){
      nivel = 0;
    }
     
    nivel_enviar = (char) floor((nivel / NIVEL_MAXIMO * 255));
    printf("\tActual tank level = %lf m\n", nivel);
    escrever(psoc_handle, &nivel_enviar, 1);
  }
}

double rungekutta(double alpha_entrada, double alpha_saida, double nivel){
  double vazao = VAZAO_MAX*alpha_entrada;
  
  nivel = (eqDiferencial(vazao, nivel, alpha_saida)*PASSO) + nivel; 

  return nivel;
}

double eqDiferencial(double vazao, double nivel, double alpha_saida){
  
 return  (vazao - (alpha_saida * AREA_DUTO)*sqrt(2*g*nivel))/ AREA_TANQUE;
}
		

MA's comunicacao.h:

#include <stdlib.h>
#include <stdio.h>
#include <unistd.h>
#include <fcntl.h>
#include <termios.h>
#include <string.h> // needed for memset

int abrir_porta(char* device);
void escrever(int file_handle, char c[], int count);
size_t ler(int file_handle, char* c, int count);
void teste(int file_handle); 
		

MA's comunicacao.c

#include <stdlib.h>
#include <stdio.h>
#include <unistd.h>
#include <fcntl.h>
#include <termios.h>
#include <string.h> // needed for memset
#include "comunicacao.h"

#define DISPOSITIVO "/dev/ttyACM0"

int abrir_porta(char* device){ // -1 deu falha
  int file_handle;
  struct termios tio;
  struct termios stdio;
  
  memset(&stdio,0,sizeof(stdio));
  stdio.c_iflag=0;
  stdio.c_oflag=0;
  stdio.c_cflag=0;
  stdio.c_lflag=0;
  stdio.c_cc[VMIN]=1;
  stdio.c_cc[VTIME]=0;
  fcntl(STDIN_FILENO, F_SETFL, O_NONBLOCK);       // make the reads non-blocking

  memset(&tio,0,sizeof(tio));
  tio.c_iflag=0;
  tio.c_oflag=0;
  tio.c_cflag=CS8|CREAD|CLOCAL;           // 8n1, see termios.h for more information
  tio.c_lflag=0;
  tio.c_cc[VMIN]=1;
  tio.c_cc[VTIME]=5;
    
  file_handle = open(device, O_RDWR | O_NONBLOCK);      
  cfsetospeed(&tio,B9600);            // 9600 baud
  cfsetispeed(&tio,B9600);            // 9600 baud  
  
  tcsetattr(file_handle,TCSANOW,&tio);
  
  return file_handle;
}

void escrever(int file_handle, char c[], int count){
  write(file_handle, c, count);
}

size_t ler(int file_handle, char* c, int count){
  return read(file_handle, c, count);
}

void teste(int file_handle){
  int i;
  char c_enviado;
  char c_recebido;
  size_t n_bytes_lidos = 0;
  char chars_enviar[5] = {'a', 'b', 'c', 'd', 'e'};

  
  for(i = 0; i < 30; i++){ //os dois primeiros n sao lidos por alguma motivo 
    c_enviado = chars_enviar[i % 5];
    printf("Enviando = %c\n", c_enviado);
    escrever(file_handle,&c_enviado,1);
    
    usleep(550 * 1000);
    
    n_bytes_lidos = ler(file_handle,&c_recebido,1);
    printf("n_bytes_lidos = %d\n", (int)n_bytes_lidos); // Retorna -1 se der erro
    printf("Lido = %c\n", c_recebido);
  }
}
		

2. DAMs

The DAM codes are written to run on an Atmega2560 (Arduino Mega).

The signal that comes to the DAM-1 is a PWM with the value of the input flow on the tank. Therefore, it is a driver for a PWM signal to be converted in a value between 0 and 255 and send to the MCM.

ADAM-1:

#define F_CPU 16000000UL
#include <avr/io.h>
#include <util/delay.h>
 
#define BAUDRATE 9600
#define BAUD_PRESCALLER (((F_CPU / (BAUDRATE * 16UL))) - 1)

//Definição das funções
void init_USART(void);
unsigned char receive(void);
void send( unsigned char data);

int main (void){
  int pin = 7;
  unsigned long duration, T = 100, ta, t1;  
  unsigned char byte_envio,byte_recebimento;

  init_USART();
  pinMode(pin, INPUT);
  
  while(1){
    duration = pulseIn(pin, HIGH)/1000;
    
    if (duration/T > 1)
      duration = 100;
    byte_envio = (floor(((float)duration/T) * 255));
    send (byte_envio);
  }
  
  return 0;
}

void init_USART(void){
 UBRR0H = (uint8_t)(BAUD_PRESCALLER>>8);
 UBRR0L = (uint8_t)(BAUD_PRESCALLER);
 UCSR0B = (1 << RXEN0)|(1 << TXEN0);
 UCSR0C = (3 << UCSZ00);
}
unsigned char receive(void){
 
 while(!(UCSR0A & (1 << RXC0)));
 return UDR0;
 
}
void send( unsigned char data){
 
 while(!(UCSR0A & (1 << UDRE0)));
 UDR0 = data;
 
}
		

The second input signal is a voltage value from 0 to 5 volts. Therefore, the DAM-2 code must implement an Analog-to-Digital conversion.

ADAM-2:

#define F_CPU 16000000UL
#include <avr/io.h>
#include <util/delay.h>
 
#define BAUDRATE 9600
#define BAUD_PRESCALLER (((F_CPU / (BAUDRATE * 16UL))) - 1)

//Definição de funções
void USART_init(void);
unsigned char USART_receive(void);
void USART_send( unsigned char data);

int main (void){
  //Configura os parametros para a comunicação serial
  USART_init();
  
  //Declaração de variáveis	
  float percentual_abertura;
  unsigned char byte_envio,byte_recebimento;

 //Habilita o ADC e seta o prescale do seu contador como 64*
  ADCSRA |= _BV(ADEN) | (1<<ADPS0) | (1<<ADPS1);

  //Configura o ADC para ler da entrada ADC0 com referencia externa
  ADMUX |= 0b00000000;
  ADMUX &= 0b11110000;
  
  //Pino 13 como saída
  pinMode(13, OUTPUT);
  
  while(1){  
    //Inicia a conversao A/D e aguarda a finalização
    ADCSRA |= _BV(ADSC);
    while(!(ADCSRA & _BV(ADIF)));
    
    //Cálculo do percentual_abertura para a válvula com base no valor do ADC
    percentual_abertura = (float)(ADC/512.0);
    if(percentual_abertura <= 1.0 || percentual_abertura >= 0){
      digitalWrite(13, HIGH);
    }else {
      digitalWrite(13, LOW);
    }
    
    //Adequando valor para envio
    byte_envio = (unsigned char) floor(percentual_abertura * 255.0);
    
    //Envio pela porta serial
    USART_send(byte_envio);
  }
  
  return 0;
}

void USART_init(void){
 UBRR0H = (uint8_t)(BAUD_PRESCALLER>>8);
 UBRR0L = (uint8_t)(BAUD_PRESCALLER);
 UCSR0B = (1 << RXEN0)|(1 << TXEN0);
 UCSR0C = (3 << UCSZ00);
}
unsigned char USART_receive(void){
 
 while(!(UCSR0A & (1 << RXC0)));
 return UDR0;
 
}
void USART_send( unsigned char data){
 
 while(!(UCSR0A & (1 << UDRE0)));
 UDR0 = data;
 
}
		

3. SGM

The SGM receives a digital signal from the MCM. It's output signal form the simulation is a voltage signal representing the height of water in the tank. Therefore, it must implement a Digital-to-Analog conversion.

To do this, a PSoC Development Kit was used. The used micro-controller was the PSoC 3 device. The components were used as shown below:

Figure 1

Figure 1: Components of SGM implementation on a PSoC 3.

ASGM:

#include <device.h>
#include "stdio.h"

#if defined (__GNUC__)
    /* Add an explicit reference to the floating point printf library */
    /* to allow the usage of floating point conversion specifiers. */
    /* This is not linked in by default with the newlib-nano library. */
    asm (".global _printf_float");
#endif


#define BUFFER_LEN  64u

char8 *parity[] = { "None", "Odd", "Even", "Mark", "Space" };
char8 *stop[] = { "1", "1.5", "2" };

void main()
{
    uint16 count;
    uint8 buffer[BUFFER_LEN];
    char8 lineStr[20];
    uint8 state;
    
    /* Enable Global Interrupts */
    CyGlobalIntEnable;                        

    /* Start USBFS Operation with 3V operation */
    USBUART_1_Start(0u, USBUART_1_3V_OPERATION);

    /* Start LCD */
    LCD_Start();
    LCD_PrintString("USB-UART example");
    
    /* Wait for Device to enumerate */
    while(!USBUART_1_GetConfiguration());
    
    VDAC8_1_Start();

    /* Enumeration is done, enable OUT endpoint for receive data from Host */
    USBUART_1_CDC_Init();

    /* Main Loop: */
    for(;;)
    {
        if(USBUART_1_DataIsReady() != 0u)               /* Check for input data from PC */
        {
            count = USBUART_1_GetAll(buffer);           /* Read received data and re-enable OUT endpoint */
            if(count != 0u)
            {
                sprintf(lineStr,"Rec:%c",buffer[0]);
                LCD_Position(0u, 0u);
                LCD_PrintString("                    ");
                LCD_Position(0u, 0u);
                LCD_PrintString(lineStr);
                VDAC8_1_SetValue(buffer[0]);
            }
        } 
    }   
}
/* [] END OF FILE */