Modification du code driver DC + Ajout code de test
This commit is contained in:
@@ -16,7 +16,7 @@
|
||||
*/
|
||||
#include <EEPROM.h>
|
||||
#include "PID_v1.h"
|
||||
#define encoder0PinA 2 // PD2;
|
||||
#define encoder0PinA 7 // PD2;
|
||||
#define encoder0PinB 8 // PC0;
|
||||
#define M1 9
|
||||
#define M2 10 // motor's PWM outputs
|
||||
|
||||
@@ -33,7 +33,7 @@
|
||||
//from ramps 1.4 stepper driver
|
||||
#define STEP_PIN 3 //PD3;
|
||||
#define DIR_PIN 5 //PC0;
|
||||
//#define ENABLE_PIN 13 //PB5; for now is USELESS
|
||||
//#define ENABLE_PIN 11 //PB5; for now is USELESS
|
||||
|
||||
//to use current motor as speed control, the LMD18245 has 4 bit cuttent output
|
||||
//#define M0 9 //assign 4 bit from PORTB register to current control -> Bxx0000x (x mean any)
|
||||
|
||||
66
Moteur DC/Test/Test_Moteur_DC/Test_Moteur_DC.ino
Normal file
66
Moteur DC/Test/Test_Moteur_DC/Test_Moteur_DC.ino
Normal file
@@ -0,0 +1,66 @@
|
||||
int motor1Pin1 = 9; // pin 2 (Input 1) du L293D
|
||||
int motor1Pin2 = 10; // pin 7 (Input 2) du L293D
|
||||
int enablePin = 11; // pin 1 (Enable 1) du L293D
|
||||
|
||||
void setup() {
|
||||
// set all the other pins you're using as outputs:
|
||||
pinMode(motor1Pin1, OUTPUT);
|
||||
pinMode(motor1Pin2, OUTPUT);
|
||||
pinMode(enablePin, OUTPUT);
|
||||
|
||||
// Mettre la broche Enable a high comme ca le moteur tourne
|
||||
digitalWrite(enablePin, HIGH);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
// Le moteur tourne dans un sens
|
||||
digitalWrite(motor1Pin1, LOW); // mettre pin 2 a 293D low
|
||||
digitalWrite(motor1Pin2, HIGH); // mettre pin 7 a L293D high
|
||||
|
||||
delay( 100 );
|
||||
|
||||
// Le moteur tourne dans l'autre sens
|
||||
digitalWrite(motor1Pin1, HIGH); // Mettre pin 2 a L293D high
|
||||
digitalWrite(motor1Pin2, LOW); // Mettre pin 7 a L293D low
|
||||
|
||||
delay( 100 );
|
||||
|
||||
// Le moteur tourne dans un sens
|
||||
digitalWrite(motor1Pin1, LOW); // mettre pin 2 a 293D low
|
||||
digitalWrite(motor1Pin2, HIGH); // mettre pin 7 a L293D high
|
||||
|
||||
delay( 50 );
|
||||
|
||||
// Le moteur tourne dans l'autre sens
|
||||
digitalWrite(motor1Pin1, HIGH); // Mettre pin 2 a L293D high
|
||||
digitalWrite(motor1Pin2, LOW); // Mettre pin 7 a L293D low
|
||||
|
||||
delay( 50 );
|
||||
|
||||
// Le moteur tourne dans un sens
|
||||
digitalWrite(motor1Pin1, LOW); // mettre pin 2 a 293D low
|
||||
digitalWrite(motor1Pin2, HIGH); // mettre pin 7 a L293D high
|
||||
|
||||
delay( 100 );
|
||||
|
||||
// Le moteur tourne dans l'autre sens
|
||||
digitalWrite(motor1Pin1, HIGH); // Mettre pin 2 a L293D high
|
||||
digitalWrite(motor1Pin2, LOW); // Mettre pin 7 a L293D low
|
||||
|
||||
delay( 100 );
|
||||
|
||||
|
||||
// Le moteur tourne dans un sens
|
||||
digitalWrite(motor1Pin1, LOW); // mettre pin 2 a 293D low
|
||||
digitalWrite(motor1Pin2, HIGH); // mettre pin 7 a L293D high
|
||||
|
||||
delay( 200 );
|
||||
|
||||
// Le moteur tourne dans l'autre sens
|
||||
digitalWrite(motor1Pin1, HIGH); // Mettre pin 2 a L293D high
|
||||
digitalWrite(motor1Pin2, LOW); // Mettre pin 7 a L293D low
|
||||
|
||||
delay( 200 );
|
||||
|
||||
}
|
||||
|
||||
36
Moteur DC/Test/Test_Roue_Codeuse/Test_Roue_Codeuse.ino
Normal file
36
Moteur DC/Test/Test_Roue_Codeuse/Test_Roue_Codeuse.ino
Normal file
@@ -0,0 +1,36 @@
|
||||
/* Read Quadrature Encoder
|
||||
* Connect Encoder to Pins encoder0PinA, encoder0PinB, and +5V.
|
||||
*
|
||||
* Sketch by max wolf / www.meso.net
|
||||
* v. 0.1 - very basic functions - mw 20061220
|
||||
*
|
||||
*/
|
||||
|
||||
|
||||
int val;
|
||||
int encoder0PinA = 7;
|
||||
int encoder0PinB = 8;
|
||||
int encoder0Pos = 0;
|
||||
int encoder0PinALast = LOW;
|
||||
int n = LOW;
|
||||
|
||||
void setup() {
|
||||
pinMode (encoder0PinA,INPUT);
|
||||
pinMode (encoder0PinB,INPUT);
|
||||
Serial.begin (9600);
|
||||
}
|
||||
|
||||
void loop() {
|
||||
n = digitalRead(encoder0PinA);
|
||||
if ((encoder0PinALast == LOW) && (n == HIGH)) {
|
||||
if (digitalRead(encoder0PinB) == LOW) {
|
||||
encoder0Pos--;
|
||||
} else {
|
||||
encoder0Pos++;
|
||||
}
|
||||
Serial.print (encoder0Pos);
|
||||
Serial.print ("\n");
|
||||
}
|
||||
encoder0PinALast = n;
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user