#include
#include "Adafruit_VL53L0X.h"
#include
#define HALFSTEP 8
/// motor 1 pins
#define motorPin1 32 // IN1 on the ULN2003 driver 1
#define motorPin2 33 // IN2 on the ULN2003 driver 1
#define motorPin3 34 // IN3 on the ULN2003 driver 1
#define motorPin4 35
// motor 2 pins
#define motorPin5 28 // IN1 on the ULN2003 driver 1
#define motorPin6 29 // IN2 on the ULN2003 driver 1
#define motorPin7 30 // IN3 on the ULN2003 driver 1
#define motorPin8 31 // IN4 on the ULN2003 driver 1
// motor 3 pins
#define motorPin9 16 // IN1 on the ULN2003 driver 2
#define motorPin10 15 // IN2 on the ULN2003 driver 2
#define motorPin11 14 // IN3 on the ULN2003 driver 2
#define motorPin12 13 // IN4 on the ULN2003 driver 2
// motor 4 pins
#define motorPin13 9 // IN1 on the ULN2003 driver 2
#define motorPin14 10 // IN2 on the ULN2003 driver 2
#define motorPin15 11 // IN3 on the ULN2003 driver 2
#define motorPin16 12 // IN4 on the ULN2003 driver 2
// motor 5 pins
#define motorPin17 41 // IN1 on the ULN2003 driver 3
#define motorPin18 42 // IN2 on the ULN2003 driver 3
#define motorPin19 43 // IN3 on the ULN2003 driver 3
#define motorPin20 44 // IN4 on the ULN2003 driver 3
// motor 6 pins
#define motorPin21 40 // IN1 on the ULN2003 driver 3
#define motorPin22 39 // IN2 on the ULN2003 driver 3
#define motorPin23 38 // IN3 on the ULN2003 driver 3
#define motorPin24 37 // IN4 on the ULN2003 driver 3
// Joystick pins
#define joyX A0 // X-axis pin
#define joyY A1 // Y-axis pin
// Initialize motors with pin sequences
AccelStepper stepper1(HALFSTEP, motorPin1, motorPin3, motorPin2, motorPin4);
AccelStepper stepper2(HALFSTEP, motorPin5, motorPin7, motorPin6, motorPin8);
AccelStepper stepper3(HALFSTEP, motorPin9, motorPin11, motorPin10, motorPin12);
AccelStepper stepper4(HALFSTEP, motorPin13, motorPin15, motorPin14, motorPin16);
AccelStepper stepper5(HALFSTEP, motorPin17, motorPin19, motorPin18, motorPin20);
AccelStepper stepper6(HALFSTEP, motorPin21, motorPin23, motorPin22, motorPin24);
// Variables
int joystickX = 0;
int joystickY = 0;
int joystickThreshold = 100; // Sensitivity threshold for the joystick
int maxSpeed = 1200; // Maximum speed for the motors
bool read_sensor_flag = false;
long int sensor_time_out = 0;
// Sensor addresses
#define LOX1_ADDRESS 0x30
#define LOX2_ADDRESS 0x31
#define LOX3_ADDRESS 0x32
// Shutdown pins
#define SHT_LOX1 23
#define SHT_LOX2 24
#define SHT_LOX3 25
#define NUM_SAMPLES 12
int sensor1Values[NUM_SAMPLES];
int sensor2Values[NUM_SAMPLES];
int sensor3Values[NUM_SAMPLES];
// Initialize VL53L0X sensors
Adafruit_VL53L0X lox1 = Adafruit_VL53L0X();
Adafruit_VL53L0X lox2 = Adafruit_VL53L0X();
Adafruit_VL53L0X lox3 = Adafruit_VL53L0X();
VL53L0X_RangingMeasurementData_t measure1;
VL53L0X_RangingMeasurementData_t measure2;
VL53L0X_RangingMeasurementData_t measure3;
void setID() {
// Reset sensors
digitalWrite(SHT_LOX1, LOW);
digitalWrite(SHT_LOX2, LOW);
digitalWrite(SHT_LOX3, LOW);
delay(10);
digitalWrite(SHT_LOX1, HIGH);
digitalWrite(SHT_LOX2, HIGH);
digitalWrite(SHT_LOX3, HIGH);
delay(10);
// Initialize LOX1
digitalWrite(SHT_LOX1, HIGH);
digitalWrite(SHT_LOX2, LOW);
digitalWrite(SHT_LOX3, LOW);
if (!lox1.begin(LOX1_ADDRESS)) {
Serial.println(F("Failed to boot first VL53L0X"));
} else {
Serial.println(F("First VL53L0X address 0x30 initialized"));
}
delay(100);
// Initialize LOX2
digitalWrite(SHT_LOX2, HIGH);
digitalWrite(SHT_LOX3, LOW);
if (!lox2.begin(LOX2_ADDRESS)) {
Serial.println(F("Failed to boot second VL53L0X"));
} else {
Serial.println(F("Second VL53L0X address 0x31 initialized"));
}
delay(100);
// Initialize LOX3
digitalWrite(SHT_LOX3, HIGH);
if (!lox3.begin(LOX3_ADDRESS)) {
Serial.println(F("Failed to boot third VL53L0X"));
} else {
Serial.println(F("Third VL53L0X address 0x32 initialized"));
}
delay(100);
}
void readSensorsAndPrintAverage() {
for (int i = 0; i < NUM_SAMPLES; i++) {
lox1.rangingTest(&measure1, false);
lox2.rangingTest(&measure2, false);
lox3.rangingTest(&measure3, false);
sensor1Values[i] = measure1.RangeStatus != 4 ? measure1.RangeMilliMeter : 0;
sensor2Values[i] = measure2.RangeStatus != 4 ? measure2.RangeMilliMeter : 0;
sensor3Values[i] = measure3.RangeStatus != 4 ? measure3.RangeMilliMeter : 0;
delay(50); // Задержка между измерениями
}
// Вычисление средних значений с исключением наибольшего и наименьшего
float averageDistance1 = calculateAverageWithOutliersRemoved(sensor1Values);
float averageDistance2 = calculateAverageWithOutliersRemoved(sensor2Values);
float averageDistance3 = calculateAverageWithOutliersRemoved(sensor3Values);
if (averageDistance1 > 0 && averageDistance2 > 0 && averageDistance3 > 0) {
// Calculate average distance only if all measurements are valid
float averageDistance = (averageDistance1 + averageDistance2 + averageDistance3) / 3.0;
Serial.print(F("D1: "));
Serial.print(averageDistance1);
Serial.print(F(" mm, D2: "));
Serial.print(averageDistance2);
Serial.print(F(" mm, D3: "));
Serial.print(averageDistance3);
Serial.print(F(" mm, AD: "));
Serial.print(averageDistance);
Serial.println(F(" mm"));
} else {
Serial.println(F("One or more distances out of range"));
}
}
float calculateAverageWithOutliersRemoved(int values[]) {
// Найдем наибольшее и наименьшее значения в массиве
int minValue = values[0];
int maxValue = values[0];
int sum = 0;
for (int i = 0; i < NUM_SAMPLES; i++) {
if (values[i] < minValue) minValue = values[i];
if (values[i] > maxValue) maxValue = values[i];
sum += values[i];
}
// Удалим наибольшее и наименьшее значения из суммы и рассчитаем среднее
sum -= minValue;
sum -= maxValue;
// Вернем среднее значение оставшихся (NUM_SAMPLES - 2) элементов
return sum / (float)(NUM_SAMPLES - 2);
}
void setup() {
// Set maximum speed and acceleration for both motors
stepper1.setMaxSpeed(maxSpeed);
stepper1.setAcceleration(500.0);
stepper2.setMaxSpeed(maxSpeed);
stepper2.setAcceleration(500.0);
stepper3.setMaxSpeed(maxSpeed);
stepper3.setAcceleration(500.0);
stepper4.setMaxSpeed(maxSpeed);
stepper4.setAcceleration(500.0);
stepper5.setMaxSpeed(maxSpeed);
stepper5.setAcceleration(500.0);
stepper6.setMaxSpeed(maxSpeed);
stepper6.setAcceleration(500.0);
// Initialize serial communication for debugging
Serial.begin(115200);
while (!Serial) { delay(1); }
pinMode(SHT_LOX1, OUTPUT);
pinMode(SHT_LOX2, OUTPUT);
pinMode(SHT_LOX3, OUTPUT);
// Serial.println(F("Shutdown pins initialized..."));
digitalWrite(SHT_LOX1, LOW);
digitalWrite(SHT_LOX2, LOW);
digitalWrite(SHT_LOX3, LOW);
// Serial.println(F("Sensors in reset mode"));
setID();
}
void loop() {
// Read joystick values
joystickX = analogRead(joyX) - 512; // Center the joystick reading to the range -512 to 512
joystickY = analogRead(joyY) - 512;
// Control motor 1 (X-axis control)
controlMotor1(joystickX);
controlMotor2(joystickX);
controlMotor3(joystickX);
// Control motor 2 (Y-axis control)
controlMotor4(joystickY);
controlMotor5(joystickY);
controlMotor6(joystickY);
// Run the motors
stepper1.runSpeed();
stepper2.runSpeed();
stepper3.runSpeed();
stepper4.runSpeed();
stepper5.runSpeed();
stepper6.runSpeed();
sensor_time_out++;
if (sensor_time_out > 2000)
{
readSensorsAndPrintAverage();
sensor_time_out=0;
}
}
// Control motor 1 based on X-axis of the joystick
void controlMotor1(int joystickX) {
if (abs(joystickX) > joystickThreshold) {
int motor1Speed = map(joystickX, -510, 510, -maxSpeed, maxSpeed);
stepper1.setSpeed(motor1Speed);
} else {
stepper1.setSpeed(0); // Stop motor 1 if joystick is in neutral position
}
}
// Control motor 2 based on Y-axis of the joystick
void controlMotor2(int joystickX) {
if (abs(joystickX) > joystickThreshold) {
int motor2Speed = map(joystickX, -510, 510, -maxSpeed, maxSpeed);
stepper2.setSpeed(motor2Speed);
} else {
stepper2.setSpeed(0); // Stop motor 2 if joystick is in neutral position
}
}
void controlMotor3(int joystickX) {
if (abs(joystickX) > joystickThreshold) {
int motor3Speed = map(joystickX, -510, 510, -maxSpeed, maxSpeed);
stepper3.setSpeed(motor3Speed);
} else {
stepper3.setSpeed(0); // Stop motor 1 if joystick is in neutral position
}
}
void controlMotor4(int joystickY) {
if (abs(joystickY) > joystickThreshold) {
int motor4Speed = map(joystickY, -510, 510, -maxSpeed, maxSpeed);
stepper4.setSpeed(motor4Speed);
} else {
stepper4.setSpeed(0); // Stop motor 1 if joystick is in neutral position
}
}
void controlMotor5(int joystickY) {
if (abs(joystickY) > joystickThreshold) {
int motor5Speed = map(joystickY, -510, 510, -maxSpeed, maxSpeed);
stepper5.setSpeed(motor5Speed);
} else {
stepper5.setSpeed(0); // Stop motor 1 if joystick is in neutral position
}
}
void controlMotor6(int joystickY) {
if (abs(joystickY) > joystickThreshold) {
int motor6Speed = map(joystickY, -510, 510, -maxSpeed, maxSpeed);
stepper6.setSpeed(motor6Speed);
} else {
stepper6.setSpeed(0); // Stop motor 1 if joystick is in neutral position
}
}