ajout capteur distance du sol

This commit is contained in:
dd060606
2025-05-24 15:56:33 +02:00
parent 074ccf7a57
commit 9167637101
4 changed files with 85 additions and 16 deletions

6
.vscode/settings.json vendored Normal file
View File

@@ -0,0 +1,6 @@
{
"cmake.sourceDirectory": "D:/Electronique/ESP32/PAMI-2025/lib/bluepad32/src",
"files.associations": {
"iterator": "cpp"
}
}

View File

@@ -6,8 +6,8 @@
{
"type": "board-esp32-devkit-c-v4",
"id": "esp",
"top": 180.74,
"left": -265.1,
"top": 171.14,
"left": -274.7,
"rotate": 90,
"attrs": {}
},
@@ -47,6 +47,28 @@
"top": 203.1,
"left": -71.3,
"attrs": {}
},
{
"type": "wokwi-text",
"id": "text1",
"top": 163.2,
"left": -19.2,
"attrs": { "text": "Obstacles" }
},
{
"type": "wokwi-hc-sr04",
"id": "ultrasonic2",
"top": 470.9,
"left": -357.9,
"rotate": 180,
"attrs": {}
},
{
"type": "wokwi-text",
"id": "text2",
"top": 508.8,
"left": -182.4,
"attrs": { "text": "Capteur de chutes" }
}
],
"connections": [
@@ -69,7 +91,9 @@
["esp:16", "drv1:DIR", "blue", ["v9.6", "h144"]],
["esp:4", "drv3:DIR", "blue", ["v19.2", "h-57.6", "v-201.6"]],
["ultrasonic1:TRIG", "esp:18", "violet", ["v76.8", "h-221.2"]],
["ultrasonic1:ECHO", "esp:5", "violet", ["v86.4", "h-240.8"]]
["ultrasonic1:ECHO", "esp:5", "violet", ["v86.4", "h-240.8"]],
["esp:15", "ultrasonic2:ECHO", "cyan", ["v0"]],
["esp:17", "ultrasonic2:TRIG", "cyan", ["v115.2", "h-38.4"]]
],
"dependencies": {}
}

View File

@@ -14,16 +14,31 @@ enum Direction
#define TX_PIN 17
#define RX_PIN 16
/* Réel */
// PINs réels
#ifndef SIMULATOR
// Moteur 1 - Gauche
#define M1_DIR_PIN 18
#define M1_STEP_PIN 22
#define M1_ENABLE_PIN 32
// Moteur 2 - Droite
#define M2_DIR_PIN 19
#define M2_STEP_PIN 23
#define M2_ENABLE_PIN 26
/* Simulateur
// Capteur à ultrasons
#define TRIG_PIN 14
#define ECHO_PIN 15
// Capteur de chute
#define FALL_TRIG_PIN 12
#define FALL_ECHO_PIN 13
#endif
// PINs pour le simulateur
#ifdef SIMULATOR
// Moteur 1 - Gauche
#define M1_DIR_PIN 4
@@ -35,7 +50,15 @@ enum Direction
#define M2_STEP_PIN 32
#define M2_ENABLE_PIN 27
*/
// Capteur à ultrasons
#define TRIG_PIN 18
#define ECHO_PIN 5
// Capteur de chute
#define FALL_TRIG_PIN 17
#define FALL_ECHO_PIN 15
#endif
// Paramètres moteurs
#define R_SENSE 0.11f
@@ -44,10 +67,6 @@ enum Direction
#define DRIVER1_ADDR 0b00
#define DRIVER2_ADDR 0b01
// Capteur à ultrasons
#define TRIG_PIN 18
#define ECHO_PIN 5
// Constantes pour les roues
#define WHEEL_DIAMETER 5.5 // cm
#define STEPS_PER_REV 200 * 16 // microsteps

View File

@@ -1,6 +1,7 @@
#include <Arduino.h>
#include <TMCStepper.h>
#define SIMULATOR // Commenter cette ligne pour utiliser le matériel réel
// Définitions des constantes dans main.h
#include "main.h"
@@ -129,18 +130,31 @@ const int obstacleCheckInterval = 100; // ms between distance checks
unsigned long lastObstacleCheckTime = 0;
const int obstacleThresholdCM = 20; // stop if closer than 20 cm
long readDistanceCM()
long readDistanceCM(uint8_t trigPin, uint8_t echoPin)
{
digitalWrite(TRIG_PIN, LOW);
digitalWrite(trigPin, LOW);
delayMicroseconds(2);
digitalWrite(TRIG_PIN, HIGH);
digitalWrite(trigPin, HIGH);
delayMicroseconds(10);
digitalWrite(TRIG_PIN, LOW);
long duration = pulseIn(ECHO_PIN, HIGH, 20000); // timeout 20 ms
digitalWrite(trigPin, LOW);
long duration = pulseIn(echoPin, HIGH, 20000); // timeout 20 ms
long distance = duration * 0.034 / 2;
return distance;
}
// Vérification de la distance du sol pour éviter les chutes
void checkFall()
{
long fallDistance = readDistanceCM(FALL_TRIG_PIN, FALL_ECHO_PIN);
// On a fini notre chemin si on arrive en bout de table (détection de distance du sol si plus de 5 cm)
if (fallDistance > 5.0 && movementInProgress)
{
stopMotors();
movementInProgress = false;
Serial.println("Bout de table détecté : Arrêt");
}
}
void detectObstacles()
{
// On vérifie les obstacles
@@ -149,13 +163,16 @@ void detectObstacles()
{
lastObstacleCheckTime = now;
// On regarde la distance du sol
checkFall();
// Si le robot tourne sur lui-même, on ne vérifie pas les obstacles
if (lastDirection == RIGHT || lastDirection == LEFT)
{
return;
}
long distance = readDistanceCM();
long distance = readDistanceCM(TRIG_PIN, ECHO_PIN);
if (distance > 0 && distance < obstacleThresholdCM)
{
@@ -203,6 +220,9 @@ void setup()
// Capteur à ultrasons
pinMode(TRIG_PIN, OUTPUT);
pinMode(ECHO_PIN, INPUT);
// Capteur de chute
pinMode(FALL_TRIG_PIN, OUTPUT);
pinMode(FALL_ECHO_PIN, INPUT);
digitalWrite(M1_ENABLE_PIN, LOW);
digitalWrite(M2_ENABLE_PIN, LOW);