esp8266超声波自动避障小车
sean 编辑于2021-06-07 10:38硬件相关
这个小车前面有三个超声波测距传感器,除了特别小的障碍物,基本上可以实现自动避障。其实esp8266更适合遥控,同样的硬件有遥控版的代码在另一篇文章里。
这货长这样
esp8266 电机驱动板,接口对应node mcu esp8266接口的定义:
上代码:
// connections for drive Motors
int PWM_L = 5; //GPIO5 ,D1
int PWM_R = 4; //GPIO4 ,D2
int DIR_L = 0; //GPIO0, D3
int DIR_R = 2; //GPIO2, D4
//set utralsonic pin
#define TRIG_L 14 //D5, GPIO14
#define ECHO_L 12 //D6, GPIO12
#define TRIG_R 13 //D7, GPIO13
#define ECHO_R 15 //D8, GPIO15
#define TRIG_M 9 //SD2, GPIO9
#define ECHO_M 10 //SD3, GPIO10
int distance_l;
int distance_r;
int distance_m;
String command; // String to store app command state.
int SPEED = 1020; // 330 - 1023.
int speed_Coeff = 3 ; //转弯系数
int left_count; //计数器,指令执行次数,防止无限循环。
int right_count;
int command_left_count = 0; //用于控制遥控命令的左右转的幅度
int command_right_count = 0;
int is_forward = 1; //0 停止前进,1可以前进
int is_backward_step = 0; //往后退几步
int is_turn_right = 0;
int is_turn_left = 0;
void setup() {
Serial.begin(115200); // set up Serial library at 115200 bps
Serial.println();
Serial.println("*WiFi Robot Remote Control Mode*");
Serial.println("--------------------------------------");
pinMode(ECHO_L, INPUT); //Set EchoPin as input, to receive measure result from US-025,US-026
pinMode(TRIG_L, OUTPUT);
pinMode(ECHO_R, INPUT); //Set EchoPin as input, to receive measure result from US-025,US-026
pinMode(TRIG_R, OUTPUT);
pinMode(ECHO_M, INPUT);
pinMode(TRIG_M, OUTPUT);
// Set all the motor control pins to outputs
pinMode(PWM_L, OUTPUT);
pinMode(PWM_R, OUTPUT);
pinMode(DIR_L, OUTPUT);
pinMode(DIR_R, OUTPUT);
// Turn off motors - Initial state
digitalWrite(DIR_L, LOW);
digitalWrite(DIR_R, LOW);
analogWrite(PWM_L, 0);
analogWrite(PWM_R, 0);
}
void loop() {
distance_l = get_left_distance();
distance_r = get_right_distance();
distance_m = get_mid_distance();
if ( ( (distance_l >= 5608) || ( (distance_l > 0) && (distance_l < 250)) ) && ( (distance_m >= 5608) || ( (distance_m > 0) && (distance_m < 250)) ) && ( (distance_r >= 5608) || ( (distance_r > 0) && (distance_r < 250)) ) ) {
//0, 0, 0 停止前进,倒退默认向右转
Backward_step();
if ( distance_r > distance_l ) {
TurnRight();
}
else {
TurnLeft();
}
}
else if ( ( (distance_m == 5609) || ( (distance_m > 0) && (distance_m < 250)) || (distance_m == 5608) ) && ((distance_l < 5608) && (distance_l >= 250)) && ((distance_r < 5608) && (distance_r >= 250)) ) {
//1, 0, 1中间有障碍, 后退并选择方向转一步
Backward_step();
if ( distance_r > distance_l ) {
TurnRight();
}
else {
TurnLeft();
}
}
else if ( (((distance_l > 0) && (distance_l < 250)) || (distance_l == 5609) || (distance_l == 5608) ) && ( ((distance_m >= 250 ) && (distance_m < 5608)) ) && ((distance_r < 5608) && (distance_r >= 250)) ) {
//0,1,1左边有障碍,直接往右转,然后前进
Backward_step();
TurnRight();
}
else if ( (((distance_l > 0) && (distance_l < 250)) || (distance_l == 5609) || (distance_l == 5608) ) && ( ((distance_m > 0) && (distance_m < 250)) || (distance_m == 5609) || (distance_m == 5608)) && ((distance_r < 5608) && (distance_r >= 250)) ) {
//0,0,1左边和中间有障碍,后退并右转
Backward_step();
TurnRight();
}
else if ( (((distance_r > 0) && (distance_r < 250)) || (distance_r == 5609) || (distance_r == 5608) ) && ( ((distance_m >= 250 ) && (distance_m < 5608)) ) && ((distance_l < 5608) && (distance_l >= 250))) {
//1,1,0 右边有障碍, 左转并前进
Backward_step();
TurnLeft();
}
else if ( (((distance_r > 0) && (distance_r < 250)) || (distance_r >= 5608) ) && ( ((distance_m > 0) && (distance_m < 250)) || (distance_m >= 5608) ) && ((distance_l < 5608) && (distance_l >= 250)) ) {
//1, 0, 0右边和中间有障碍, 停下并左转
Backward_step();
TurnLeft();
}
else if ( ( (distance_l >= 5608) || ( (distance_l > 0) && (distance_l < 250)) ) && ( (distance_m > 250) && (distance_m < 5608) ) && ( (distance_r >= 5608) || ( (distance_r > 0) && (distance_r < 250)) ) ) {
//0, 1, 0 继续前进
Forward();
}
else if ( ( (distance_l > 250) && (distance_l < 5608) ) && ( (distance_m > 250) && (distance_m < 5608) ) && ( (distance_r > 250) && (distance_r < 5608) ) ) {
//1, 1, 1 继续前进
Forward();
}
}
int get_mid_distance() {
unsigned long Time_Echo_us = 0;
unsigned long Len_mm = 0;
digitalWrite(TRIG_M, HIGH); //begin to send a high pulse, then US-025/US-026 begin to measure the distance
delayMicroseconds(20); //set this high pulse width as 20us (>10us)
digitalWrite(TRIG_M, LOW); //end this high pulse
Time_Echo_us = pulseIn(ECHO_M, HIGH); //calculate the pulse width at EchoPin,
if ((Time_Echo_us < 60000) && (Time_Echo_us > 1)) //a valid pulse width should be between (1, 60000).
{
Len_mm = (Time_Echo_us * 34 / 100) / 2; //calculate the distance by pulse width, Len_mm = (Time_Echo_us * 0.34mm/us) / 2 (mm)
Serial.print("Present M_Distance is: "); //output result to Serial monitor
//Serial.print(Len_mm, DEC); //output result to Serial monitor
Serial.print(Len_mm);
Serial.println("mm"); //output result to Serial monitor
return Len_mm;
}
else {
return 0;
}
}
int get_left_distance() {
unsigned long Time_Echo_us = 0;
unsigned long Len_mm = 0;
digitalWrite(TRIG_L, HIGH); //begin to send a high pulse, then US-025/US-026 begin to measure the distance
delayMicroseconds(20); //set this high pulse width as 20us (>10us)
digitalWrite(TRIG_L, LOW); //end this high pulse
Time_Echo_us = pulseIn(ECHO_L, HIGH); //calculate the pulse width at EchoPin,
if ((Time_Echo_us < 60000) && (Time_Echo_us > 1)) //a valid pulse width should be between (1, 60000).
{
Len_mm = (Time_Echo_us * 34 / 100) / 2; //calculate the distance by pulse width, Len_mm = (Time_Echo_us * 0.34mm/us) / 2 (mm)
Serial.print("Present L_Distance is: "); //output result to Serial monitor
//Serial.print(Len_mm, DEC); //output result to Serial monitor
Serial.print(Len_mm);
Serial.println("mm"); //output result to Serial monitor
return Len_mm;
}
else {
return 0;
}
}
int get_right_distance() {
unsigned long Time_Echo_us = 0;
unsigned long Len_mm = 0;
digitalWrite(TRIG_R, HIGH); //begin to send a high pulse, then US-025/US-026 begin to measure the distance
delayMicroseconds(20); //set this high pulse width as 20us (>10us)
digitalWrite(TRIG_R, LOW); //end this high pulse
Time_Echo_us = pulseIn(ECHO_R, HIGH); //calculate the pulse width at EchoPin,
if ((Time_Echo_us < 60000) && (Time_Echo_us > 1)) //a valid pulse width should be between (1, 60000).
{
Len_mm = (Time_Echo_us * 34 / 100) / 2; //calculate the distance by pulse width, Len_mm = (Time_Echo_us * 0.34mm/us) / 2 (mm)
Serial.print("Present R_Distance is: "); //output result to Serial monitor
//Serial.print(Len_mm, DEC); //output result to Serial monitor
Serial.print(Len_mm);
Serial.println("mm"); //output result to Serial monitor
return Len_mm;
}
else {
return 0;
}
}
//void handle_404() {
// server.send(404, "text/plain", "404: Not found"); // Send HTTP status 404 (Not Found) when there's no handler for the URI in the request
//}
// function to stop motors
void Stop() {
digitalWrite(DIR_L, LOW);
digitalWrite(DIR_R, LOW);
analogWrite(PWM_L, 0);
analogWrite(PWM_R, 0);
delay(300);
}
// function to move forward
void Forward() {
digitalWrite(DIR_L, HIGH);
digitalWrite(DIR_R, HIGH);
analogWrite(PWM_L, SPEED);
analogWrite(PWM_R, SPEED);
}
// function to move backward
void Backward() {
digitalWrite(DIR_L, LOW);
digitalWrite(DIR_R, LOW);
analogWrite(PWM_L, SPEED);
analogWrite(PWM_R, SPEED);
}
void Backward_step() {
//往后退n步,然后根据需要往左或往右转,然后再开启前进使能
digitalWrite(DIR_L, LOW);
digitalWrite(DIR_R, LOW);
analogWrite(PWM_L, SPEED);
analogWrite(PWM_R, SPEED);
delay(300);
analogWrite(PWM_L, 0);
analogWrite(PWM_R, 0);
delay(300);
}
// function to turn right
void TurnRight() {
digitalWrite(DIR_L, HIGH);
digitalWrite(DIR_R, LOW);
analogWrite(PWM_L, SPEED);
analogWrite(PWM_R, SPEED);
delay(200);
analogWrite(PWM_L, 0);
analogWrite(PWM_R, 0);
delay(300);
}
// function to turn left
void TurnLeft() {
digitalWrite(DIR_L, LOW);
digitalWrite(DIR_R, HIGH);
analogWrite(PWM_L, SPEED);
analogWrite(PWM_R, SPEED);
delay(200);
analogWrite(PWM_L, 0);
analogWrite(PWM_R, 0);
delay(300);
}
关于本站
肥龙软件分享的软件是本站作者开发的免费,无广告,安全可靠,绝不附带任何无关软件,绝不困绑任何插件的实用软件。如果您感觉好用,可以捐赠我们,这样我们可以有更积极的动力去改进升级软件,维持服务器运转,感谢您的捐助,谢谢!
致谢 赞赏/捐助名单
更新时间:2024.8.31
联系作者(邮箱)
软件