Accel working, Temp working, two way communication basically wrking
This commit is contained in:
146
src/receiver.cpp
146
src/receiver.cpp
@ -4,18 +4,39 @@
|
||||
#include "SSD1306.h"
|
||||
#include <esp_now.h>
|
||||
#include <WiFi.h>
|
||||
#include <OneWire.h>
|
||||
#include <DallasTemperature.h>
|
||||
|
||||
#include "mac_config.h"
|
||||
|
||||
#define esc1pin 15
|
||||
#define esc2pin 13
|
||||
#define fallbackpin 36
|
||||
#define failsafeValue 127
|
||||
#define ONE_WIRE_BUS 14
|
||||
#define fanRelais 16
|
||||
|
||||
#define DELETEBEFOREPAIR 0
|
||||
|
||||
Servo esc1;
|
||||
Servo esc2;
|
||||
SSD1306 display(0x3c, 5, 4);
|
||||
|
||||
|
||||
OneWire oneWire(ONE_WIRE_BUS);
|
||||
DallasTemperature sensors(&oneWire); // one instance for all sensrs
|
||||
|
||||
esp_now_peer_info_t remote;
|
||||
|
||||
float temperature = 0;
|
||||
float voltage = 0;
|
||||
float speed = 0;
|
||||
|
||||
uint8_t sendTemperature = 0;
|
||||
uint8_t sendTemperatureDecimals = 0;
|
||||
uint8_t sendVoltage = 0;
|
||||
uint8_t sendSpeed = 0;
|
||||
|
||||
//#define pairingMode
|
||||
#define CONNECTION_TIMEOUT 300
|
||||
#define CHANNEL 1
|
||||
@ -39,7 +60,7 @@ void writeServos(uint8_t firstServo, uint8_t secondServo) {
|
||||
esc2.write(secondServo);
|
||||
}
|
||||
|
||||
// callback when data is recv from Master
|
||||
// callback when data is recv from remote
|
||||
void OnDataRecv(const uint8_t *mac_addr, const uint8_t *data, int data_len) {
|
||||
char macStr[18];
|
||||
snprintf(macStr, sizeof(macStr), "%02x:%02x:%02x:%02x:%02x:%02x",
|
||||
@ -49,6 +70,31 @@ void OnDataRecv(const uint8_t *mac_addr, const uint8_t *data, int data_len) {
|
||||
memcpy(recData, data, data_len);
|
||||
Serial.print("Last Packet Recv Data: "); Serial.println(recData[0]); Serial.print(" "); Serial.print(recData[1]); Serial.print(" len:"); Serial.println(data_len);
|
||||
|
||||
// Answer with response
|
||||
const uint8_t respData[] = { sendTemperature, sendTemperatureDecimals, sendVoltage }; // sendSpeed
|
||||
Serial.print("Sending RESPONSE.... ");
|
||||
esp_err_t result = esp_now_send(mac_addr, respData, sizeof(data));
|
||||
if (result == ESP_OK) {
|
||||
Serial.println("Success");
|
||||
} else if (result == ESP_ERR_ESPNOW_NOT_INIT) {
|
||||
// How did we get so far!!
|
||||
Serial.println("ESPNOW not Init.");
|
||||
} else if (result == ESP_ERR_ESPNOW_ARG) {
|
||||
Serial.println("Invalid Argument");
|
||||
} else if (result == ESP_ERR_ESPNOW_INTERNAL) {
|
||||
Serial.println("Internal Error");
|
||||
} else if (result == ESP_ERR_ESPNOW_NO_MEM) {
|
||||
Serial.println("ESP_ERR_ESPNOW_NO_MEM");
|
||||
} else if (result == ESP_ERR_ESPNOW_NOT_FOUND) {
|
||||
Serial.println("Peer not found.");
|
||||
} else if (result == ESP_ERR_ESPNOW_IF) {
|
||||
Serial.println("ESP_ERR_ESPNOW_IF");
|
||||
} else {
|
||||
Serial.println("Not sure what happened");
|
||||
}
|
||||
|
||||
|
||||
|
||||
lastPacket = millis();
|
||||
isConnected = true;
|
||||
// Could check mac here for some security
|
||||
@ -61,8 +107,90 @@ void OnDataRecv(const uint8_t *mac_addr, const uint8_t *data, int data_len) {
|
||||
display.display();
|
||||
}
|
||||
|
||||
void deletePeer() {
|
||||
const esp_now_peer_info_t *peer = &remote;
|
||||
const uint8_t *peer_addr = remote.peer_addr;
|
||||
esp_err_t delStatus = esp_now_del_peer(peer_addr);
|
||||
Serial.print("Slave Delete Status: ");
|
||||
if (delStatus == ESP_OK) {
|
||||
// Delete success
|
||||
Serial.println("Success");
|
||||
} else if (delStatus == ESP_ERR_ESPNOW_NOT_INIT) {
|
||||
// How did we get so far!!
|
||||
Serial.println("ESPNOW Not Init");
|
||||
} else if (delStatus == ESP_ERR_ESPNOW_ARG) {
|
||||
Serial.println("Invalid Argument");
|
||||
} else if (delStatus == ESP_ERR_ESPNOW_NOT_FOUND) {
|
||||
Serial.println("Peer not found.");
|
||||
} else {
|
||||
Serial.println("Not sure what happened");
|
||||
}
|
||||
}
|
||||
|
||||
bool manageRemote() {
|
||||
if (remote.channel == CHANNEL) {
|
||||
if (DELETEBEFOREPAIR) {
|
||||
deletePeer();
|
||||
}
|
||||
|
||||
Serial.print("Remote Status: ");
|
||||
const esp_now_peer_info_t *peer = &remote;
|
||||
const uint8_t *peer_addr = remote.peer_addr;
|
||||
// check if the peer exists
|
||||
bool exists = esp_now_is_peer_exist(peer_addr);
|
||||
if ( exists) {
|
||||
// Slave already paired.
|
||||
Serial.println("Already Paired");
|
||||
return true;
|
||||
} else {
|
||||
// Slave not paired, attempt pair
|
||||
esp_err_t addStatus = esp_now_add_peer(peer);
|
||||
if (addStatus == ESP_OK) {
|
||||
// Pair success
|
||||
Serial.println("Pair success");
|
||||
return true;
|
||||
} else if (addStatus == ESP_ERR_ESPNOW_NOT_INIT) {
|
||||
// How did we get so far!!
|
||||
Serial.println("ESPNOW Not Init");
|
||||
return false;
|
||||
} else if (addStatus == ESP_ERR_ESPNOW_ARG) {
|
||||
Serial.println("Invalid Argument");
|
||||
return false;
|
||||
} else if (addStatus == ESP_ERR_ESPNOW_FULL) {
|
||||
Serial.println("Peer list full");
|
||||
return false;
|
||||
} else if (addStatus == ESP_ERR_ESPNOW_NO_MEM) {
|
||||
Serial.println("Out of memory");
|
||||
return false;
|
||||
} else if (addStatus == ESP_ERR_ESPNOW_EXIST) {
|
||||
Serial.println("Peer Exists");
|
||||
return true;
|
||||
} else {
|
||||
Serial.println("Not sure what happened");
|
||||
return false;
|
||||
}
|
||||
}
|
||||
} else {
|
||||
// No slave found to process
|
||||
Serial.println("No Slave found to process");
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// end ESPNOW functions
|
||||
|
||||
|
||||
void checkTemperature() {
|
||||
sensors.requestTemperatures(); // Send the command to get temperatures
|
||||
temperature = sensors.getTempCByIndex(0);
|
||||
Serial.print("Temp: ");
|
||||
Serial.println(temperature);
|
||||
if(temperature < 35) digitalWrite(fanRelais, LOW);
|
||||
if(temperature > 40) digitalWrite(fanRelais, HIGH);
|
||||
sendTemperature = (uint16_t) temperature;
|
||||
sendTemperatureDecimals = (uint16_t)(temperature - sendTemperature) *100;
|
||||
}
|
||||
|
||||
void setup() {
|
||||
Serial.begin(115200);
|
||||
Serial.println("ESPNowSkate Receiver");
|
||||
@ -76,6 +204,10 @@ void setup() {
|
||||
esc1.attach(esc1pin, 0, 0, 255, 1100, 1900);
|
||||
esc2.attach(esc2pin, 1, 0, 255, 1100, 1900);
|
||||
|
||||
sensors.begin();
|
||||
|
||||
pinMode(fanRelais, OUTPUT);
|
||||
|
||||
//Set device in AP mode to begin with
|
||||
WiFi.mode(WIFI_AP);
|
||||
// configure device AP mode
|
||||
@ -95,9 +227,19 @@ void setup() {
|
||||
Serial.println("ESPNow Init Failed");
|
||||
ESP.restart();
|
||||
}
|
||||
|
||||
// Once ESPNow is successfully Init, we will register for recv CB to
|
||||
// get recv packer info.
|
||||
esp_now_register_recv_cb(OnDataRecv);
|
||||
|
||||
for (int i = 0; i < 6; ++i ) {
|
||||
remote.peer_addr[i] = (uint8_t) mac_remote[i];
|
||||
}
|
||||
|
||||
remote.channel = CHANNEL; // pick a channel
|
||||
remote.encrypt = 0; // no encryption
|
||||
remote.ifidx = ESP_IF_WIFI_AP;
|
||||
manageRemote();
|
||||
}
|
||||
|
||||
|
||||
@ -113,4 +255,6 @@ void loop() {
|
||||
display.drawString(2, 0, buf);
|
||||
display.display();
|
||||
}
|
||||
|
||||
checkTemperature();
|
||||
}
|
||||
|
Reference in New Issue
Block a user