PRESENTATION ELECTRONIQUE SOFTWARE VISION MECANIQUE LE FORUM
    NEWS DU PROJET
 
2008-01-07 23:20:08
BONNE ET HEUREUSE ANNEE 2008
L'équipe du projet Robot-Serveur vous souhaite à tous une bonne et heureuse année. Qu'elle vous...Plus de détails...

2007-09-07 20:19:36
STATU QUO
Depuis quelques mois, le projet est à l'arrêt. Cela est du à nos emplois du temps respectif et à...Plus de détails...

2007-03-15 21:22:31
NOUVEAU SERVEUR
Le site est en place sur son nouveau serveur( un 90plan chez OVH). Pour vous, pour le moment, c'est...Plus de détails...

 
SOFTWARE
Code C18
Noyau Picos18
Alternatives
L'ESSENTIEL
Sondage
Description
Carte principale
Code C18
Vision  
Prototype
RESSOURCES
Forum
Téléchargement
Liens
Vidéos  
Livre d or  
Contact
 
www.robot-serveur.net
SOFTWARE
 
Une des versions du programme est écrite avec le compilateur C18 fourni par Microchip. Elle est écrite à la manière d'un code C classique. Les interruptions sont très utilisées, afin d'obtenir un temps de réaction le plus court possible.
Le code actuel permet au robot de se déplacer dans une pièce en évitant les obstacles, mais le comportement du robot est totalement du robot est parfaitement arbitraire: il ne contourne pas l'obstacle, mais se contente de tourner dans la direction opposée pour l'éviter. Il continue alors à avancer tout droit.
Etat actuel du programme: Le programme gère:
  • la vitesse des moteurs avec les modules PWM (un par moteur) grâce aux fonctions:
    1. void Init_Moteurs(void):
      Initialisation des deux modules PWM à la fréquence de découpage
    2. void Stop_Moteurs(void):
      Freinage ( blocage des roues, pas de roue libre)
    3. void Acceleration(int vitesse):
      Accélération progressive jusqu'a la valeur passée en argument (pour éviter de démarrer d'un coup)

  • le moteur pas à pas de la tourelle télémètre (pas à pas 4 fils):
    void tourelle(int position):
    Déplace le moteur pas à pas dans la position passée en argument: 12 correspond a la position initiale ( droit devant), la valeur de position est comprise entre 0 et 24 pour effectuer un demi-tour.

  • la distance des obstacles grâce au télémètre GP2D12

  • la lecture/écriture dans l'eeprom interne:
    1. static void Write_Eeprom(int adresse, int data)
    2. static int Read_Eeprom(int adresse)

  • les chocs sur l'avant par interruption sur le portB


Tout cela est détaillé dans la documentation du code C18 du projet, disponible ici ou dans la section téléchargement.

Le programme:
/***************************************
			Robot serveur
			 Version 1.0

Dernière révision:22/05/05
				  structures globales

fonctionnalités: évitement obstacles par 
					télémètre
				détection des chocs
***************************************/
/*
//Configration du PIC
#pragma config OSC = HSPLL
#pragma config PWRT = ON
#pragma config WDT = OFF
#pragma config BOR = ON
#pragma config BORV = 42
#pragma config LVP = ON
*/


//Include
#include <p18f452.h>
#include <delays.h>
#include <timers.h>
#include <pwm.h>
#include <adc.h>
#include <portb.h>
#include "valeur_GP2D12.h"

//define

	//define des paramètres de pilotage des moteurs (L298)
#define EA LATCbits.LATC2 
#define IN1 LATCbits.LATC5
#define IN2 LATCbits.LATC0
#define EB LATCbits.LATC1
#define IN3 LATCbits.LATC4
#define IN4 LATCbits.LATC3

#define AVANT {IN1 = 1;IN2 = 0;IN3 = 1;IN4 = 0;}
#define ARRIERE {IN1 = 0;IN2 = 1;IN3 = 0;IN4 = 1;}

#define GAUCHE {IN1 = 1;IN2 = 0;IN3 = 0;IN4 = 1;}
#define DROITE {IN1 = 0;IN2 = 1;IN3 = 1;IN4 = 0;}
#define GAUCHE_ID 1
#define DROITE_ID 2

#define VITESSE_MAXI 900

	//define des moustaches
#define MOUS_D PORTBbits.RB7
#define MOUS_G PORTBbits.RB6

	//define des leds de visualisation pour debug
#define DEBUG LATBbits.LATB0
#define DEBUG_INT LATBbits.LATB1

	//define des emplacements et valeurs EEPROM
#define A_POSITION_TOURELLE 0


//declaration des variables globales

int position =12;
int tempo_conversion =0;
int adresse =0;

struct{
int distance_tourelle ;
int distance_gauche ;
int distance_droite ;
int position_tourelle;
int vitesse;
}robot_status;

struct {
signed sens_moteur_G:0;
signed sens_moteur_D:0;
unsigned vitsse_moteur_G;
unsigned vitsse_moteur_D;
}moteur_status;

//declaration des fonctions
static void Write_Eeprom(int adresse, int data);
static int Read_Eeprom(int adresse);
static void Disable_All_Interrupt(void);
static void Enable_All_Interrupt(void);
void tourelle(int position);
void Init_Moteurs(void);
void Stop_Moteurs(void);
void Acceleration(int vitesse);
int Conversion_AN(void);
void Test_Obstacle(void);
void Decalage(int direction);
void Delay(int boucle);

//gestion des interruptions
#pragma interrupt MyInterrupt save=PROD, section(".tmpdata")
void MyInterrupt(void)
{
	DEBUG_INT = 1;
	if (INTCONbits.RBIF == 1)  //changement d'état sur RB4 a RB7
		{ 
		Delay1KTCYx(150);	// anti-rebond logiciel ( à améliorer)
		if (!MOUS_D && !MOUS_G)
			{		
			Stop_Moteurs();	
			DEBUG = 1;
			Delay10KTCYx(0);
			Delay10KTCYx(0);
			DEBUG = 0;
			ARRIERE
			Acceleration(VITESSE_MAXI);
			Delay(1);
			Stop_Moteurs();
			Delay(1);
			Decalage(GAUCHE_ID);
			AVANT
			}
		if (!MOUS_D) 
			{		
			Stop_Moteurs();	
			DEBUG = 1;
			Delay10KTCYx(0);
			Delay10KTCYx(0);
			DEBUG = 0;
			ARRIERE
			Acceleration(VITESSE_MAXI);
			Delay(1);
			Stop_Moteurs();
			Delay(1);
			Decalage(GAUCHE_ID);
			AVANT
			}
		else if (!MOUS_G) 
			{	
			Stop_Moteurs();		
			DEBUG = 1;
			Delay10KTCYx(0);
			Delay10KTCYx(0);
			DEBUG = 0;
			ARRIERE
			Acceleration(VITESSE_MAXI);
			Delay(1);
			Stop_Moteurs();
			Delay(1);
			Decalage(DROITE_ID);
			AVANT
			}
	INTCONbits.RBIF = 0; //repositionne le bit à 0 pour autoriser à nouveau
		}		//l'interruption

	if (PIR1bits.TMR2IF)	//débordement du timer2
		{
		if(tempo_conversion == 40)
			{
			tempo_conversion =0;
			SetChanADC(ADC_CH0);
			robot_status.distance_tourelle = Conversion_AN();
			SetChanADC(ADC_CH1);
			robot_status.distance_droite = Conversion_AN();
			SetChanADC(ADC_CH2);
			robot_status.distance_gauche = Conversion_AN();
			}
		else tempo_conversion++;
		PIR1bits.TMR2IF = 0; //repositionne le bit à 0 
		}
	DEBUG_INT = 0;
	return;
}
#pragma code highVector=0x008
void atInterrupthigh(void)
{
_asm GOTO MyInterrupt _endasm	
}
#pragma code 

//fonctions
static void Write_Eeprom(int adresse, int data)
{
	EEADR = adresse;
	EEDATA = data;
	EECON1bits.EEPGD = 0;
	EECON1bits.CFGS =0;
	EECON1bits.WREN =1;
	Disable_All_Interrupt();
	_asm
	MOVLW 0x55
	MOVWF EECON2,0
	MOVLW 0xAA
	MOVWF EECON2,0
	_endasm
	EECON1bits.WR=1;
	while (EECON1bits.WR == 1);
	EECON1bits.WREN = 0;
	Enable_All_Interrupt();
	return;
}

static int Read_Eeprom(int adresse)
{
	EEADR = adresse;
	EECON1bits.RD = 1;
	EECON1bits.EEPGD = 0;
	EECON1bits.CFGS = 0;
	return EEDATA;
}

static void Disable_All_Interrupt(void) //désactive toutes les interruptions (à revoir)
{
	while(INTCONbits.GIEH) INTCONbits.GIEH=0;
	INTCONbits.GIE = 0;
	INTCONbits.PEIE = 1;
}

static void Enable_All_Interrupt(void) //active toutes les interruptions ( à revoir)
{
	while(INTCONbits.GIEL) INTCONbits.GIEL=0;
	INTCONbits.GIE = 1;
	INTCONbits.PEIE = 1;
}

void tourelle(int position) //deplace le moteur pas à pas dans la postion souhaitée
{
	int i;
	int sequence[] = 
		{
		0b10101, 
		0b10001, 
		0b11001, 
		0b11000, 
		0b11010, 
		0b10010, 
		0b10110, 
		0b10100
		};

	if(position > robot_status.position_tourelle)
		{
		while(position != robot_status.position_tourelle)
			{
			for(i=0; i<7; i++)
				{
				LATD = sequence[i];
				Delay10KTCYx(25);
				}
			robot_status.position_tourelle++;
			Write_Eeprom(A_POSITION_TOURELLE,robot_status.position_tourelle);
			}
		LATDbits.LATD5 = 0;
		}
	
	else if(position < robot_status.position_tourelle)
		{
		while(position != robot_status.position_tourelle)
			{
			for(i=7; i>0; i--)
				{
				LATD = sequence[i];
				Delay10KTCYx(25);
				}
			robot_status.position_tourelle--;
			Write_Eeprom(A_POSITION_TOURELLE,robot_status.position_tourelle);
			}
		LATDbits.LATD5 = 0;
		}
		
}

void Init_Moteurs(void)
{
	OpenPWM1(255);
	OpenPWM2(255);
	SetDCPWM1(0);
	SetDCPWM2(0);
}

void Stop_Moteurs(void) // (à améliorer)
{
//	SetDCPWM1(1023);
//	SetDCPWM2(1023);
/*
	ClosePWM1();
	ClosePWM2();
	EA = 1;
	EB = 1;
*/
	IN1 = 1;
	IN2 = 1;
	IN3 = 1;
	IN4 = 1;

}

void Acceleration(int vitesse) //accéleration progressive jusqu'a la valeur spécifiée
{
		for(robot_status.vitesse; robot_status.vitesse <=vitesse; robot_status.vitesse++)
		{
		SetDCPWM1(robot_status.vitesse);
		SetDCPWM2(robot_status.vitesse);
		Delay1KTCYx(25);
		}
	return;
}

int Conversion_AN(void) //effectue une conversion AN
{
	int result = 0;
	Disable_All_Interrupt();
	ConvertADC();
	while( BusyADC() );
	result = ReadADC();
	Enable_All_Interrupt();
	return(result);
}

void Decalage(int direction)
{

	if( direction == GAUCHE_ID)
		{
		GAUCHE
		}
	if( direction == DROITE_ID)
		{
		DROITE
		}
	Acceleration(625);
	Delay10KTCYx(180);
	Stop_Moteurs();
	tourelle(12);
}



void Test_Obstacle(void)
{
	if(robot_status.distance_tourelle < dist_capteur1[6])  
		{
		AVANT;
		Acceleration(VITESSE_MAXI);
		}
	else
		{
		DEBUG =1;
		Stop_Moteurs();
		Delay(1);
		Decalage(GAUCHE_ID);
		} 
	if( robot_status.distance_gauche > dist_capteur1[5])
		{
		Decalage(DROITE_ID);
		}
	else if ( robot_status.distance_droite > dist_capteur1[5]) 
		{
		Decalage(GAUCHE_ID);
		}
	else
		{
		AVANT;
		Acceleration(VITESSE_MAXI);
		}
}


//fonction principale
void main(void)
{

int position = 0;
int i=0;

robot_status.vitesse = 500;
robot_status.position_tourelle = 12 ;

Disable_All_Interrupt();

	//E/S
TRISA = 255 ;	// portA en entree

TRISB = 0b11111000 ; 	//portB en entree sauf B0 et B1 et B2
OpenPORTB(PORTB_CHANGE_INT_ON & PORTB_PULLUPS_ON); //RB4 a RB7 interruption sur changement d'état
INTCON2bits.RBIP = 1; //priorité haute
INTCONbits.RBIF = 0;  // clear

TRISC = 0x00; ;	//portC en sortie

TRISD = 0x00;	//portD en sortie

	//conv A/n
OpenADC(ADC_FOSC_2 & ADC_8ANA_0REF & ADC_RIGHT_JUST,ADC_CH0 &ADC_CH1 &ADC_CH2 & ADC_INT_OFF); 
//CloseADC();

	//Timers
OpenTimer0(TIMER_INT_OFF & T0_16BIT & T0_SOURCE_EXT & T0_EDGE_RISE & T0_PS_1_1);
OpenTimer1(TIMER_INT_OFF & T1_16BIT_RW & T1_SOURCE_EXT & T1_PS_1_1 & T1_OSC1EN_OFF & T1_SYNC_EXT_OFF);
OpenTimer2(TIMER_INT_ON & T2_PS_1_16 & T2_POST_1_16);

	//PWM 
Init_Moteurs();

DEBUG = 1;
Delay10KTCYx(0);
Delay10KTCYx(0);
DEBUG = 0;
Delay10KTCYx(0);

Enable_All_Interrupt();

while(1)
{
	while(robot_status.position_tourelle <=16)
		{
		robot_status.position_tourelle +=1;
		tourelle(robot_status.position_tourelle);
		Test_Obstacle();
		}
	while(robot_status.position_tourelle >=8)
		{
		robot_status.position_tourelle -=1;
		tourelle(robot_status.position_tourelle);
		Test_Obstacle();
		}
}

DEBUG = 1;

}

//fonctions annexes
void Delay(int boucle)
{
	int i;
	for(i=0;i<= boucle;i++)
		{
		Delay10KTCYx(0);
		}
	return;
}



Rédigé par Harry_Tauper le 19/11/05
FORUM
 
PARTENAIRES  


   lelectronique.com : Le premier portail consacré à lélectronique     



PUBLICITE  


iGraal