这个是从YouTube上搬运来的,如图所示
https://github.com/un0038998/ESPNOW_Car
其中:
接收端(左图)和发送端(右图)
第一步: 获取接收端esp32的mac地址
把接收端的esp32插入电脑,烧录下面的代码,通过串口查看mac地址
#include "WiFi.h"
void setup()
{
Serial.begin(115200);
WiFi.mode(WIFI_MODE_STA);
Serial.println(WiFi.macAddress());
}
void loop()
{
}
第二步:把mac地址粘贴到发送端的代码中
发送端代码
#include
#include
#define X_AXIS_PIN 32
#define Y_AXIS_PIN 33
#define SWITCH_PIN 25
// 把上一步中,“接收端”的mac地址,按照这个格式,替代一下!!!!
// 把上一步中,“接收端”的mac地址,按照这个格式,替代一下!!!!
// 把上一步中,“接收端”的mac地址,按照这个格式,替代一下!!!!
uint8_t receiverMacAddress[] = {0xAC,0x67,0xB2,0x36,0x7F,0x28}; //AC:67:B2:36:7F:28
struct PacketData
{
byte xAxisValue;
byte yAxisValue;
byte switchPressed;
};
PacketData data;
//This function is used to map 0-4095 joystick value to 0-254. hence 127 is the center value which we send.
//It also adjust the deadband in joystick.
//Jotstick values range from 0-4095. But its center value is not always 2047. It is little different.
//So we need to add some deadband to center value. in our case 1800-2200. Any value in this deadband range is mapped to center 127.
int mapAndAdjustJoystickDeadBandValues(int value, bool reverse)
{
if (value >= 2200)
{
value = map(value, 2200, 4095, 127, 254);
}
else if (value <= 1800)
{
value = map(value, 1800, 0, 127, 0);
}
else
{
value = 127;
}
if (reverse)
{
value = 254 - value;
}
return value;
}
// callback when data is sent
void OnDataSent(const uint8_t *mac_addr, esp_now_send_status_t status)
{
Serial.print("\r\nLast Packet Send Status:\t ");
Serial.println(status);
Serial.println(status == ESP_NOW_SEND_SUCCESS ? "Message sent" : "Message failed");
}
void setup()
{
Serial.begin(115200);
WiFi.mode(WIFI_STA);
// Init ESP-NOW
if (esp_now_init() != ESP_OK)
{
Serial.println("Error initializing ESP-NOW");
return;
}
else
{
Serial.println("Succes: Initialized ESP-NOW");
}
esp_now_register_send_cb(OnDataSent);
// Register peer
esp_now_peer_info_t peerInfo;
memcpy(peerInfo.peer_addr, receiverMacAddress, 6);
peerInfo.channel = 0;
peerInfo.encrypt = false;
// Add peer
if (esp_now_add_peer(&peerInfo) != ESP_OK)
{
Serial.println("Failed to add peer");
return;
}
else
{
Serial.println("Succes: Added peer");
}
pinMode(SWITCH_PIN, INPUT_PULLUP);
}
void loop()
{
data.xAxisValue = mapAndAdjustJoystickDeadBandValues(analogRead(X_AXIS_PIN), false);
data.yAxisValue = mapAndAdjustJoystickDeadBandValues(analogRead(Y_AXIS_PIN), false);
data.switchPressed = false;
if (digitalRead(SWITCH_PIN) == LOW)
{
data.switchPressed = true;
}
esp_err_t result = esp_now_send(receiverMacAddress, (uint8_t *) &data, sizeof(data));
if (result == ESP_OK)
{
Serial.println("Sent with success");
}
else
{
Serial.println("Error sending the data");
}
if (data.switchPressed == true)
{
delay(500);
}
else
{
delay(50);
}
}
#include
#include
//Right motor
int enableRightMotor=22;
int rightMotorPin1=16;
int rightMotorPin2=17;
//Left motor
int enableLeftMotor=23;
int leftMotorPin1=18;
int leftMotorPin2=19;
#define MAX_MOTOR_SPEED 200
const int PWMFreq = 1000; /* 1 KHz */
const int PWMResolution = 8;
const int rightMotorPWMSpeedChannel = 4;
const int leftMotorPWMSpeedChannel = 5;
#define SIGNAL_TIMEOUT 1000 // This is signal timeout in milli seconds. We will reset the data if no signal
unsigned long lastRecvTime = 0;
struct PacketData
{
byte xAxisValue;
byte yAxisValue;
byte switchPressed;
};
PacketData receiverData;
bool throttleAndSteeringMode = false;
// callback function that will be executed when data is received
void OnDataRecv(const uint8_t * mac, const uint8_t *incomingData, int len)
{
if (len == 0)
{
return;
}
memcpy(&receiverData, incomingData, sizeof(receiverData));
String inputData ;
inputData = inputData + "values " + receiverData.xAxisValue + " " + receiverData.yAxisValue + " " + receiverData.switchPressed;
Serial.println(inputData);
if (receiverData.switchPressed == true)
{
if (throttleAndSteeringMode == false)
{
throttleAndSteeringMode = true;
}
else
{
throttleAndSteeringMode = false;
}
}
if (throttleAndSteeringMode)
{
throttleAndSteeringMovements();
}
else
{
simpleMovements();
}
lastRecvTime = millis();
}
void simpleMovements()
{
if (receiverData.yAxisValue <= 75) //Move car Forward
{
rotateMotor(MAX_MOTOR_SPEED, MAX_MOTOR_SPEED);
}
else if (receiverData.yAxisValue >= 175) //Move car Backward
{
rotateMotor(-MAX_MOTOR_SPEED, -MAX_MOTOR_SPEED);
}
else if (receiverData.xAxisValue >= 175) //Move car Right
{
rotateMotor(-MAX_MOTOR_SPEED, MAX_MOTOR_SPEED);
}
else if (receiverData.xAxisValue <= 75) //Move car Left
{
rotateMotor(MAX_MOTOR_SPEED, -MAX_MOTOR_SPEED);
}
else //Stop the car
{
rotateMotor(0, 0);
}
}
void throttleAndSteeringMovements()
{
int throttle = map( receiverData.yAxisValue, 254, 0, -255, 255);
int steering = map( receiverData.xAxisValue, 0, 254, -255, 255);
int motorDirection = 1;
if (throttle < 0) //Move car backward
{
motorDirection = -1;
}
int rightMotorSpeed, leftMotorSpeed;
rightMotorSpeed = abs(throttle) - steering;
leftMotorSpeed = abs(throttle) + steering;
rightMotorSpeed = constrain(rightMotorSpeed, 0, 255);
leftMotorSpeed = constrain(leftMotorSpeed, 0, 255);
rotateMotor(rightMotorSpeed * motorDirection, leftMotorSpeed * motorDirection);
}
void rotateMotor(int rightMotorSpeed, int leftMotorSpeed)
{
if (rightMotorSpeed < 0)
{
digitalWrite(rightMotorPin1,LOW);
digitalWrite(rightMotorPin2,HIGH);
}
else if (rightMotorSpeed > 0)
{
digitalWrite(rightMotorPin1,HIGH);
digitalWrite(rightMotorPin2,LOW);
}
else
{
digitalWrite(rightMotorPin1,LOW);
digitalWrite(rightMotorPin2,LOW);
}
if (leftMotorSpeed < 0)
{
digitalWrite(leftMotorPin1,LOW);
digitalWrite(leftMotorPin2,HIGH);
}
else if (leftMotorSpeed > 0)
{
digitalWrite(leftMotorPin1,HIGH);
digitalWrite(leftMotorPin2,LOW);
}
else
{
digitalWrite(leftMotorPin1,LOW);
digitalWrite(leftMotorPin2,LOW);
}
ledcWrite(rightMotorPWMSpeedChannel, abs(rightMotorSpeed));
ledcWrite(leftMotorPWMSpeedChannel, abs(leftMotorSpeed));
}
void setUpPinModes()
{
pinMode(enableRightMotor,OUTPUT);
pinMode(rightMotorPin1,OUTPUT);
pinMode(rightMotorPin2,OUTPUT);
pinMode(enableLeftMotor,OUTPUT);
pinMode(leftMotorPin1,OUTPUT);
pinMode(leftMotorPin2,OUTPUT);
//Set up PWM for motor speed
ledcSetup(rightMotorPWMSpeedChannel, PWMFreq, PWMResolution);
ledcSetup(leftMotorPWMSpeedChannel, PWMFreq, PWMResolution);
ledcAttachPin(enableRightMotor, rightMotorPWMSpeedChannel);
ledcAttachPin(enableLeftMotor, leftMotorPWMSpeedChannel);
rotateMotor(0, 0);
}
void setup()
{
setUpPinModes();
Serial.begin(115200);
WiFi.mode(WIFI_STA);
// Init ESP-NOW
if (esp_now_init() != ESP_OK)
{
Serial.println("Error initializing ESP-NOW");
return;
}
esp_now_register_recv_cb(OnDataRecv);
}
void loop()
{
//Check Signal lost.
unsigned long now = millis();
if ( now - lastRecvTime > SIGNAL_TIMEOUT )
{
rotateMotor(0, 0);
}
}