This commit is contained in:
unknown 2026-01-22 23:15:20 +03:00
commit 71615ead86
19 changed files with 591 additions and 0 deletions

5
.gitignore vendored Normal file
View File

@ -0,0 +1,5 @@
.pio
.vscode/.browse.c_cpp.db*
.vscode/c_cpp_properties.json
.vscode/launch.json
.vscode/ipch

10
.vscode/extensions.json vendored Normal file
View File

@ -0,0 +1,10 @@
{
// See http://go.microsoft.com/fwlink/?LinkId=827846
// for the documentation about the extensions.json format
"recommendations": [
"platformio.platformio-ide"
],
"unwantedRecommendations": [
"ms-vscode.cpptools-extension-pack"
]
}

0
README.md Normal file
View File

37
include/README Normal file
View File

@ -0,0 +1,37 @@
This directory is intended for project header files.
A header file is a file containing C declarations and macro definitions
to be shared between several project source files. You request the use of a
header file in your project source file (C, C++, etc) located in `src` folder
by including it, with the C preprocessing directive `#include'.
```src/main.c
#include "header.h"
int main (void)
{
...
}
```
Including a header file produces the same results as copying the header file
into each source file that needs it. Such copying would be time-consuming
and error-prone. With a header file, the related declarations appear
in only one place. If they need to be changed, they can be changed in one
place, and programs that include the header file will automatically use the
new version when next recompiled. The header file eliminates the labor of
finding and changing all the copies as well as the risk that a failure to
find one copy will result in inconsistencies within a program.
In C, the convention is to give header files names that end with `.h'.
Read more about using header files in official GCC documentation:
* Include Syntax
* Include Operation
* Once-Only Headers
* Computed Includes
https://gcc.gnu.org/onlinedocs/cpp/Header-Files.html

46
lib/README Normal file
View File

@ -0,0 +1,46 @@
This directory is intended for project specific (private) libraries.
PlatformIO will compile them to static libraries and link into the executable file.
The source code of each library should be placed in a separate directory
("lib/your_library_name/[Code]").
For example, see the structure of the following example libraries `Foo` and `Bar`:
|--lib
| |
| |--Bar
| | |--docs
| | |--examples
| | |--src
| | |- Bar.c
| | |- Bar.h
| | |- library.json (optional. for custom build options, etc) https://docs.platformio.org/page/librarymanager/config.html
| |
| |--Foo
| | |- Foo.c
| | |- Foo.h
| |
| |- README --> THIS FILE
|
|- platformio.ini
|--src
|- main.c
Example contents of `src/main.c` using Foo and Bar:
```
#include <Foo.h>
#include <Bar.h>
int main (void)
{
...
}
```
The PlatformIO Library Dependency Finder will find automatically dependent
libraries by scanning project source files.
More information about PlatformIO Library Dependency Finder
- https://docs.platformio.org/page/librarymanager/ldf.html

19
platformio.ini Normal file
View File

@ -0,0 +1,19 @@
; PlatformIO Project Configuration File
;
; Build options: build flags, source filter
; Upload options: custom upload port, speed and extra flags
; Library options: dependencies, extra library storages
; Advanced options: extra scripting
;
; Please visit documentation for the other options and examples
; https://docs.platformio.org/page/projectconf.html
[env:esp32dev]
platform = espressif32
board = esp32dev
framework = arduino
monitor_speed = 115200
lib_deps =
adafruit/Adafruit GFX Library
adafruit/Adafruit SSD1306

59
src/actuators.cpp Normal file
View File

@ -0,0 +1,59 @@
#include <Arduino.h>
#include "config.h"
#include "actuators.h"
void actuatorsInit() {
pinMode(PIN_LB, OUTPUT);
pinMode(PIN_LF, OUTPUT);
pinMode(PIN_RB, OUTPUT);
pinMode(PIN_RF, OUTPUT);
ledcSetup(PWM_CH_L, PWM_FREQ, PWM_RES);
ledcSetup(PWM_CH_R, PWM_FREQ, PWM_RES);
ledcAttachPin(L_PWM_PIN, PWM_CH_L);
ledcAttachPin(R_PWM_PIN, PWM_CH_R);
actuatorsSetSpeed(150, 150);
actuatorsStop();
}
void actuatorsStop() {
digitalWrite(PIN_LB, HIGH);
digitalWrite(PIN_LF, HIGH);
digitalWrite(PIN_RB, HIGH);
digitalWrite(PIN_RF, HIGH);
}
void actuatorsForward() {
digitalWrite(PIN_LB, LOW);
digitalWrite(PIN_LF, HIGH);
digitalWrite(PIN_RB, LOW);
digitalWrite(PIN_RF, HIGH);
}
void actuatorsBack() {
digitalWrite(PIN_LB, HIGH);
digitalWrite(PIN_LF, LOW);
digitalWrite(PIN_RB, HIGH);
digitalWrite(PIN_RF, LOW);
}
void actuatorsLeft() {
digitalWrite(PIN_LB, HIGH);
digitalWrite(PIN_LF, LOW);
digitalWrite(PIN_RB, LOW);
digitalWrite(PIN_RF, HIGH);
}
void actuatorsRight() {
digitalWrite(PIN_LB, LOW);
digitalWrite(PIN_LF, HIGH);
digitalWrite(PIN_RB, HIGH);
digitalWrite(PIN_RF, LOW);
}
void actuatorsSetSpeed(int l, int r) {
ledcWrite(PWM_CH_L, constrain(l, 0, 255));
ledcWrite(PWM_CH_R, constrain(r, 0, 255));
}

11
src/actuators.h Normal file
View File

@ -0,0 +1,11 @@
#pragma once
void actuatorsInit();
void actuatorsStop();
void actuatorsForward();
void actuatorsBack();
void actuatorsLeft();
void actuatorsRight();
void actuatorsSetSpeed(int l, int r);

23
src/config.h Normal file
View File

@ -0,0 +1,23 @@
#pragma once
// ===== Wi-Fi =====
#define WIFI_SSID "Capybara"
#define WIFI_PASS "qq1234567890"
// ===== Motors =====
#define L_PWM_PIN 25
#define R_PWM_PIN 26
#define PIN_LB 16
#define PIN_LF 17
#define PIN_RB 18
#define PIN_RF 19
#define PWM_CH_L 0
#define PWM_CH_R 1
#define PWM_FREQ 1000
#define PWM_RES 8 // 0..255
// ===== Timing =====
#define COMMAND_TIMEOUT_MS 600

39
src/controller.cpp Normal file
View File

@ -0,0 +1,39 @@
#include "controller.h"
#include "actuators.h"
#include "config.h"
void controllerSetMode(RobotMode m) {
robot.mode = m;
controllerStop();
robot.lastCmdMs = millis();
}
void controllerStop() {
actuatorsStop();
}
bool controllerMove(const String& cmd) {
if (robot.mode != MODE_MANUAL) return false;
if (cmd == "FWD") actuatorsForward();
else if (cmd == "BACK") actuatorsBack();
else if (cmd == "LEFT") actuatorsLeft();
else if (cmd == "RIGHT") actuatorsRight();
else return false;
return true;
}
void controllerSetSpeed(int l, int r) {
robot.speedL = l;
robot.speedR = r;
actuatorsSetSpeed(l, r);
robot.lastCmdMs = millis();
}
void controllerUpdate() {
if (robot.mode == MODE_MANUAL &&
millis() - robot.lastCmdMs > COMMAND_TIMEOUT_MS) {
controllerStop();
}
}

9
src/controller.h Normal file
View File

@ -0,0 +1,9 @@
#pragma once
#include <Arduino.h>
#include "robot_state.h"
void controllerSetMode(RobotMode m);
bool controllerMove(const String& cmd);
void controllerStop();
void controllerSetSpeed(int l, int r);
void controllerUpdate();

20
src/main.cpp Normal file
View File

@ -0,0 +1,20 @@
#include <Arduino.h>
#include "actuators.h"
#include "web_server.h"
#include "controller.h"
#include "robot_state.h"
void setup() {
Serial.begin(115200);
actuatorsInit();
webServerInit();
robot.lastCmdMs = millis();
}
void loop() {
webServerLoop();
controllerUpdate();
}

18
src/robot_state.cpp Normal file
View File

@ -0,0 +1,18 @@
#include "robot_state.h"
RobotState robot = {
MODE_IDLE,
0,
150,
150
};
const char* modeToStr(RobotMode m) {
switch (m) {
case MODE_IDLE: return "IDLE";
case MODE_MANUAL: return "MANUAL";
case MODE_AUTO: return "AUTO";
case MODE_SERVICE: return "SERVICE";
default: return "?";
}
}

22
src/robot_state.h Normal file
View File

@ -0,0 +1,22 @@
#pragma once
#include <Arduino.h>
enum RobotMode {
MODE_IDLE,
MODE_MANUAL,
MODE_AUTO,
MODE_SERVICE
};
struct RobotState {
RobotMode mode;
uint32_t lastCmdMs;
int speedL;
int speedR;
};
// глобальное состояние
extern RobotState robot;
// удобный вывод
const char* modeToStr(RobotMode m);

109
src/web_server.cpp Normal file
View File

@ -0,0 +1,109 @@
#include <WiFi.h>
#include <WebServer.h>
#include "config.h"
#include "web_ui.h"
#include "controller.h"
#include "robot_state.h"
static WebServer server(80);
void handleRoot() {
server.send_P(200, "text/html; charset=utf-8", INDEX_HTML);
}
void handleCmd() {
if (!server.hasArg("c")) {
server.send(400, "text/plain", "Missing c");
return;
}
String c = server.arg("c");
c.toUpperCase();
robot.lastCmdMs = millis();
if (c == "STOP") {
controllerStop();
server.send(200, "text/plain", "OK STOP");
return;
}
if (!controllerMove(c)) {
server.send(403, "text/plain",
String("DENIED MODE=") + modeToStr(robot.mode));
return;
}
server.send(200, "text/plain", "OK " + c);
}
void handleSpeed() {
int l = server.hasArg("l") ? server.arg("l").toInt() : robot.speedL;
int r = server.hasArg("r") ? server.arg("r").toInt() : robot.speedR;
controllerSetSpeed(l, r);
server.send(200, "text/plain", "OK SPEED");
}
void handleMode() {
if (!server.hasArg("m")) {
server.send(400, "text/plain", "Missing m");
return;
}
String m = server.arg("m");
m.toUpperCase();
if (m == "IDLE") controllerSetMode(MODE_IDLE);
else if (m == "MANUAL") controllerSetMode(MODE_MANUAL);
else if (m == "AUTO") controllerSetMode(MODE_AUTO);
else {
server.send(400, "text/plain", "Unknown mode");
return;
}
server.send(200, "text/plain",
String("OK MODE=") + modeToStr(robot.mode));
}
void handleStatus() {
String json = "{";
json += "\"mode\":\"" + String(modeToStr(robot.mode)) + "\",";
json += "\"speedL\":" + String(robot.speedL) + ",";
json += "\"speedR\":" + String(robot.speedR) + ",";
json += "\"rssi\":" + String(WiFi.RSSI()) + ",";
json += "\"uptime\":" + String(millis());
json += "}";
server.send(200, "application/json", json);
}
void webServerInit() {
WiFi.mode(WIFI_STA);
WiFi.begin(WIFI_SSID, WIFI_PASS);
Serial.print("\nConnecting to Wi-Fi");
while (WiFi.status() != WL_CONNECTED) {
Serial.print("\nRetry connecting to Wi-Fi");
delay(300);
}
if (WiFi.status() == WL_CONNECTED) {
Serial.print("\nConnected. IP: ");
Serial.println(WiFi.localIP());
}
server.on("/", handleRoot);
server.on("/cmd", handleCmd);
server.on("/speed", handleSpeed);
server.on("/mode", handleMode);
server.on("/status", handleStatus);
server.begin();
}
void webServerLoop() {
server.handleClient();
}

3
src/web_server.h Normal file
View File

@ -0,0 +1,3 @@
#pragma once
void webServerInit();
void webServerLoop();

146
src/web_ui.cpp Normal file
View File

@ -0,0 +1,146 @@
#include <Arduino.h>
#include "web_ui.h"
const char INDEX_HTML[] PROGMEM = R"HTML(
<!doctype html>
<html>
<head>
<meta name="viewport" content="width=device-width, initial-scale=1" />
<meta charset="utf-8">
<title>ESP32 Robot</title>
<style>
body { font-family: sans-serif; margin: 16px; }
.grid { display: grid; grid-template-columns: 1fr 1fr 1fr; gap: 10px; max-width: 420px; }
button { font-size: 18px; padding: 18px 10px; }
.wide { grid-column: span 3; }
.row2 { margin-top: 14px; max-width: 420px; }
input[type=range]{ width: 100%; }
.muted { opacity: 0.7; font-size: 13px; }
.status { margin-top: 10px; font-family: monospace; }
</style>
</head>
<body>
<h2>ESP32 Robot</h2>
<div class="grid">
<div></div>
<button id="btnF"></button>
<div></div>
<button id="btnL"></button>
<button id="btnS"></button>
<button id="btnR"></button>
<div></div>
<button id="btnB"></button>
<div></div>
<button class="wide" id="btnStop">STOP</button>
</div>
<div class="row2">
<label>Speed: <span id="spv">150</span></label>
<input id="speed" type="range" min="0" max="255" value="150" />
<div class="muted">Tip: удерживай стрелку — робот едет. Отпустил — STOP.</div>
<div class="status" id="st"></div>
</div>
<div class="row2">
<button onclick="setMode('IDLE')">IDLE</button>
<button onclick="setMode('MANUAL')">MANUAL</button>
<button onclick="setMode('AUTO')">AUTO</button>
</div>
<script>
const st = (t) => document.getElementById('st').textContent = t;
let holdTimer = null;
async function cmd(c){
try{
const r = await fetch(`/cmd?c=${c}`);
st(await r.text());
}catch(e){
st('ERR');
}
}
async function setSpeed(v){
document.getElementById('spv').textContent = v;
try{
const r = await fetch(`/speed?l=${v}&r=${v}`);
st(await r.text());
}catch(e){
st('ERR');
}
}
async function setMode(m){
try{
const r = await fetch(`/mode?m=${m}`);
st(await r.text());
}catch(e){
st('ERR');
}
}
async function updateStatus(){
try{
const r = await fetch('/status');
const j = await r.json();
st(
`MODE=${j.mode} | ` +
`L=${j.speedL} R=${j.speedR} | ` +
`RSSI=${j.rssi}dBm | ` +
`UP=${Math.floor(j.uptime/1000)}s`
);
}catch(e){
st('STATUS ERR');
}
}
setInterval(updateStatus, 500);
// управление "пока держишь" (heartbeat)
function bindHold(btn, onPressCmd){
const press = (e)=>{
e.preventDefault();
cmd(onPressCmd);
holdTimer = setInterval(() => {
cmd(onPressCmd);
}, 200); // каждые 200 мс
};
const release = (e)=>{
e.preventDefault();
if (holdTimer) {
clearInterval(holdTimer);
holdTimer = null;
}
cmd('STOP');
};
btn.addEventListener('mousedown', press);
btn.addEventListener('touchstart', press, {passive:false});
btn.addEventListener('mouseup', release);
btn.addEventListener('mouseleave', release);
btn.addEventListener('touchend', release);
btn.addEventListener('touchcancel', release);
}
bindHold(document.getElementById('btnF'), 'FWD');
bindHold(document.getElementById('btnB'), 'BACK');
bindHold(document.getElementById('btnL'), 'LEFT');
bindHold(document.getElementById('btnR'), 'RIGHT');
document.getElementById('btnS').onclick = ()=>cmd('STOP');
document.getElementById('btnStop').onclick = ()=>cmd('STOP');
const slider = document.getElementById('speed');
slider.addEventListener('input', ()=> setSpeed(slider.value));
st('Ready');
</script>
</body>
</html>
)HTML";

4
src/web_ui.h Normal file
View File

@ -0,0 +1,4 @@
#pragma once
#include <Arduino.h>
extern const char INDEX_HTML[];

11
test/README Normal file
View File

@ -0,0 +1,11 @@
This directory is intended for PlatformIO Test Runner and project tests.
Unit Testing is a software testing method by which individual units of
source code, sets of one or more MCU program modules together with associated
control data, usage procedures, and operating procedures, are tested to
determine whether they are fit for use. Unit testing finds problems early
in the development cycle.
More information about PlatformIO Unit Testing:
- https://docs.platformio.org/en/latest/advanced/unit-testing/index.html