feat: add dual BTS7960 motor driver support
- Refactor MotorController to parameterized class with MotorPins struct - Add motor1 and motor2 instances with shared enable pins (GPIO 14, 27) - Motor 2 uses GPIO 32/33 for PWM, GPIO 36/39 for current sense - Update web UI with side-by-side dual motor control panels - Add per-motor API endpoints (/motor1/*, /motor2/*) - Add emergency stop button for both motors - Legacy endpoints map to motor1 for backwards compatibility - Update readme and AGENTS.md documentation
This commit is contained in:
13
AGENTS.md
13
AGENTS.md
@@ -4,7 +4,7 @@ This file provides guidance to agents when working with code in this repository.
|
||||
|
||||
## Project Overview
|
||||
|
||||
PlatformIO project for ESP32 LOLIN32 Rev1 controlling BTS7960 dual H-bridge motor driver (12V DC).
|
||||
PlatformIO project for ESP32 LOLIN32 Rev1 controlling **two BTS7960 dual H-bridge motor drivers** for a differential drive robot (12V DC).
|
||||
|
||||
## Build Commands
|
||||
|
||||
@@ -17,8 +17,11 @@ pio device monitor # Serial monitor (115200 baud)
|
||||
## Hardware-Specific Notes
|
||||
|
||||
- **Board**: ESP32 LOLIN32 Rev1 (use `lolin32` in platformio.ini)
|
||||
- **Motor Driver**: BTS7960 dual H-bridge - requires 4 GPIO pins (RPWM=25, LPWM=26, R_EN=27, L_EN=14)
|
||||
- **Power**: 12V DC input to motor driver - logic level is 3.3V compatible with ESP32
|
||||
- **Motor Drivers**: 2× BTS7960 dual H-bridge - shared enable pins, independent PWM and current sense
|
||||
- **Motor 1**: RPWM=25, LPWM=26, R_IS=34, L_IS=35 (PWM channels 0,1)
|
||||
- **Motor 2**: RPWM=32, LPWM=33, R_IS=36, L_IS=39 (PWM channels 2,3)
|
||||
- **Shared enables**: R_EN=27, L_EN=14 (both drivers enable together)
|
||||
- **Power**: 12V DC input to motor drivers - logic level is 3.3V compatible with ESP32
|
||||
- **WiFi**: Connects to SSID 'tami' with static IP 10.81.2.185
|
||||
- **Reference**: https://deepbluembedded.com/arduino-bts7960-dc-motor-driver/
|
||||
|
||||
@@ -27,5 +30,7 @@ pio device monitor # Serial monitor (115200 baud)
|
||||
- Use built-in `WebServer` library (NOT ESPAsyncWebServer - has enum compatibility issues with ESP32 Arduino 3.x)
|
||||
- WebServer requires `handleClient()` call in loop() - unlike async version
|
||||
- LEDC PWM at 20kHz reduces motor noise
|
||||
- Enable pins (R_EN, L_EN) must be HIGH before PWM works
|
||||
- Enable pins (R_EN, L_EN) must be HIGH before PWM works - configured once by first motor init
|
||||
- **BTS7960 is 3.3V compatible**: Inputs are TTL/CMOS compatible (VIL<0.8V, VIH>2.0V) - ESP32 GPIOs work directly without level shifters (per BTN7960 datasheet section 5.4.1)
|
||||
- **MotorController is parameterized**: Instances `motor1` and `motor2` are created with `MotorPins` struct
|
||||
- **Legacy compatibility**: `motor` macro aliases to `motor1`, legacy `/speed` and `/direction` endpoints map to motor1
|
||||
|
||||
@@ -11,22 +11,51 @@
|
||||
#define SUBNET IPAddress(255, 255, 255, 0)
|
||||
#define DNS IPAddress(10, 81, 2, 1)
|
||||
|
||||
// BTS7960 Pin Definitions
|
||||
#define L_EN_PIN 14 // Left Enable
|
||||
#define LPWM_PIN 26 // Left PWM (Reverse)
|
||||
#define L_IS_PIN 35 // Left Current Sense (ADC input only)
|
||||
// Shared Enable Pins (both drivers share these)
|
||||
#define R_EN_PIN 27 // Right Enable (shared)
|
||||
#define L_EN_PIN 14 // Left Enable (shared)
|
||||
|
||||
#define R_EN_PIN 27 // Right Enable
|
||||
#define RPWM_PIN 25 // Right PWM (Forward)
|
||||
#define R_IS_PIN 34 // Right Current Sense (ADC input only)
|
||||
// Motor 1 BTS7960 Pin Definitions
|
||||
#define RPWM1_PIN 25 // Right PWM Motor 1 (Forward)
|
||||
#define LPWM1_PIN 26 // Left PWM Motor 1 (Reverse)
|
||||
#define R_IS1_PIN 34 // Right Current Sense Motor 1 (ADC input only)
|
||||
#define L_IS1_PIN 35 // Left Current Sense Motor 1 (ADC input only)
|
||||
|
||||
// Motor 2 BTS7960 Pin Definitions
|
||||
#define RPWM2_PIN 32 // Right PWM Motor 2 (Forward)
|
||||
#define LPWM2_PIN 33 // Left PWM Motor 2 (Reverse)
|
||||
#define R_IS2_PIN 36 // Right Current Sense Motor 2 (ADC input only - VP)
|
||||
#define L_IS2_PIN 39 // Left Current Sense Motor 2 (ADC input only - VN)
|
||||
|
||||
// PWM Configuration
|
||||
#define PWM_FREQ 20000 // 20kHz - reduces motor noise
|
||||
#define PWM_RESOLUTION 8 // 8-bit resolution (0-255)
|
||||
#define PWM_CHANNEL_R 0 // LEDC channel for RPWM
|
||||
#define PWM_CHANNEL_L 1 // LEDC channel for LPWM
|
||||
#define PWM_CHANNEL_R1 0 // LEDC channel for Motor 1 RPWM
|
||||
#define PWM_CHANNEL_L1 1 // LEDC channel for Motor 1 LPWM
|
||||
#define PWM_CHANNEL_R2 2 // LEDC channel for Motor 2 RPWM
|
||||
#define PWM_CHANNEL_L2 3 // LEDC channel for Motor 2 LPWM
|
||||
#define MIN_PWM_PERCENT 20 // Minimum PWM when motor is running (%)
|
||||
|
||||
// Motor pin configuration structure
|
||||
struct MotorPins {
|
||||
uint8_t rpwm; // Right PWM pin (forward)
|
||||
uint8_t lpwm; // Left PWM pin (reverse)
|
||||
uint8_t r_is; // Right current sense pin
|
||||
uint8_t l_is; // Left current sense pin
|
||||
uint8_t pwm_channel_r; // LEDC PWM channel for right
|
||||
uint8_t pwm_channel_l; // LEDC PWM channel for left
|
||||
};
|
||||
|
||||
// Motor 1 pin configuration
|
||||
const MotorPins MOTOR1_PINS = {
|
||||
RPWM1_PIN, LPWM1_PIN, R_IS1_PIN, L_IS1_PIN, PWM_CHANNEL_R1, PWM_CHANNEL_L1
|
||||
};
|
||||
|
||||
// Motor 2 pin configuration
|
||||
const MotorPins MOTOR2_PINS = {
|
||||
RPWM2_PIN, LPWM2_PIN, R_IS2_PIN, L_IS2_PIN, PWM_CHANNEL_R2, PWM_CHANNEL_L2
|
||||
};
|
||||
|
||||
// Current Sense Configuration
|
||||
// BTS7960 current sense ratio: 8500:1 (kilo-amps)
|
||||
// With 1kΩ resistor on IS pin: V = I_motor / 8500
|
||||
|
||||
@@ -9,6 +9,9 @@ typedef void (*StallCallback)();
|
||||
|
||||
class MotorController {
|
||||
public:
|
||||
// Constructor with pin configuration and motor name
|
||||
MotorController(const MotorPins& pins, const char* name);
|
||||
|
||||
void begin();
|
||||
void setSpeed(int speed); // 0-100 percentage
|
||||
void setDirection(int dir); // -1=reverse, 0=stop, 1=forward
|
||||
@@ -20,6 +23,7 @@ public:
|
||||
float getCurrentRight(); // Current in amps (forward direction)
|
||||
float getCurrentLeft(); // Current in amps (reverse direction)
|
||||
float getCurrentActive(); // Current from active direction
|
||||
const char* getName(); // Get motor name for logging
|
||||
|
||||
// Stall detection
|
||||
bool isStalled();
|
||||
@@ -27,6 +31,9 @@ public:
|
||||
void resetStallDetection();
|
||||
|
||||
private:
|
||||
MotorPins _pins;
|
||||
const char* _name;
|
||||
|
||||
int _speed = 0;
|
||||
int _direction = 0;
|
||||
float _currentRight = 0;
|
||||
@@ -42,12 +49,20 @@ private:
|
||||
StallCallback _stallCallback = nullptr;
|
||||
unsigned long _lastDirectionChangeTime = 0;
|
||||
|
||||
// Static flag to track if enable pins are already configured
|
||||
static bool _enablePinsConfigured;
|
||||
|
||||
void applyMotorState();
|
||||
float readCurrentSense(int pin);
|
||||
void calibrateCurrentOffset();
|
||||
void checkStall();
|
||||
};
|
||||
|
||||
extern MotorController motor;
|
||||
// Two motor controller instances
|
||||
extern MotorController motor1;
|
||||
extern MotorController motor2;
|
||||
|
||||
// Legacy alias for backwards compatibility
|
||||
#define motor motor1
|
||||
|
||||
#endif
|
||||
|
||||
118
plans/dual-motor-driver.md
Normal file
118
plans/dual-motor-driver.md
Normal file
@@ -0,0 +1,118 @@
|
||||
# Dual BTS7960 Motor Driver Integration Plan
|
||||
|
||||
## Overview
|
||||
Add a second BTS7960 motor driver for differential drive robot, sharing enable pins between both drivers.
|
||||
|
||||
## Hardware Configuration
|
||||
|
||||
### Pin Assignments
|
||||
|
||||
| Function | Motor 1 | Motor 2 | Notes |
|
||||
|----------|---------|---------|-------|
|
||||
| **R_EN** | GPIO 27 | GPIO 27 (shared) | Both drivers enable together |
|
||||
| **L_EN** | GPIO 14 | GPIO 14 (shared) | Both drivers enable together |
|
||||
| **RPWM** | GPIO 25 | GPIO 32 | Forward PWM |
|
||||
| **LPWM** | GPIO 26 | GPIO 33 | Reverse PWM |
|
||||
| **R_IS** | GPIO 34 | GPIO 36 (VP) | Current sense - input only |
|
||||
| **L_IS** | GPIO 35 | GPIO 39 (VN) | Current sense - input only |
|
||||
|
||||
### Wiring Diagram
|
||||
|
||||
```
|
||||
ESP32 LOLIN32 BTS7960 #1 BTS7960 #2
|
||||
-------------- ---------- ----------
|
||||
GPIO 27 (R_EN) ------> R_EN -----------> R_EN
|
||||
GPIO 14 (L_EN) ------> L_EN -----------> L_EN
|
||||
GPIO 25 (RPWM) ------> RPWM
|
||||
GPIO 26 (LPWM) ------> LPWM
|
||||
GPIO 34 (R_IS) <------ R_IS
|
||||
GPIO 35 (L_IS) <------ L_IS
|
||||
GPIO 32 (RPWM2) --------------------> RPWM
|
||||
GPIO 33 (LPWM2) --------------------> LPWM
|
||||
GPIO 36 (R_IS2) <-------------------- R_IS
|
||||
GPIO 39 (L_IS2) <-------------------- L_IS
|
||||
```
|
||||
|
||||
## Code Changes
|
||||
|
||||
### 1. config.h - Add Motor 2 pin definitions
|
||||
|
||||
```cpp
|
||||
// Motor 2 BTS7960 Pin Definitions
|
||||
#define RPWM2_PIN 32 // Right PWM Motor 2
|
||||
#define LPWM2_PIN 33 // Left PWM Motor 2
|
||||
#define R_IS2_PIN 36 // Right Current Sense Motor 2
|
||||
#define L_IS2_PIN 39 // Left Current Sense Motor 2
|
||||
|
||||
// Motor 2 PWM Channels
|
||||
#define PWM_CHANNEL_R2 2
|
||||
#define PWM_CHANNEL_L2 3
|
||||
```
|
||||
|
||||
### 2. motor.h - Parameterized MotorController
|
||||
|
||||
```cpp
|
||||
struct MotorPins {
|
||||
uint8_t rpwm;
|
||||
uint8_t lpwm;
|
||||
uint8_t r_is;
|
||||
uint8_t l_is;
|
||||
uint8_t pwm_channel_r;
|
||||
uint8_t pwm_channel_l;
|
||||
};
|
||||
|
||||
class MotorController {
|
||||
public:
|
||||
MotorController(const MotorPins& pins, const char* name);
|
||||
void begin();
|
||||
// ... existing methods unchanged
|
||||
private:
|
||||
MotorPins _pins;
|
||||
const char* _name;
|
||||
// ... existing members
|
||||
};
|
||||
|
||||
extern MotorController motor1;
|
||||
extern MotorController motor2;
|
||||
```
|
||||
|
||||
### 3. motor.cpp - Use parameterized pins
|
||||
|
||||
- Constructor stores pin config
|
||||
- `begin()` uses `_pins.rpwm` instead of `RPWM_PIN`, etc.
|
||||
- Serial output includes motor name for debugging
|
||||
|
||||
### 4. webserver.cpp - Dual motor API
|
||||
|
||||
New endpoints:
|
||||
- `/motor1/speed`, `/motor1/direction`, `/motor1/stop`
|
||||
- `/motor2/speed`, `/motor2/direction`, `/motor2/stop`
|
||||
- `/status` - returns both motors data
|
||||
|
||||
Keep legacy endpoints mapping to motor1 for backwards compatibility.
|
||||
|
||||
### 5. main.cpp - Initialize both controllers
|
||||
|
||||
```cpp
|
||||
void setup() {
|
||||
motor1.begin();
|
||||
motor1.setStallCallback(onMotor1Stall);
|
||||
motor2.begin();
|
||||
motor2.setStallCallback(onMotor2Stall);
|
||||
// ...
|
||||
}
|
||||
|
||||
void loop() {
|
||||
handleWebServer();
|
||||
motor1.update();
|
||||
motor2.update();
|
||||
delay(1);
|
||||
}
|
||||
```
|
||||
|
||||
## Notes
|
||||
|
||||
- Enable pins are set HIGH once in motor1.begin - both drivers share them
|
||||
- GPIO 36 and 39 are valid for ADC input - they are input-only pins
|
||||
- GPIO 32 and 33 support both PWM and ADC, using them for PWM only
|
||||
- Web UI will need expansion to show both motors - consider tabbed interface or side-by-side layout
|
||||
133
readme.md
133
readme.md
@@ -1,15 +1,16 @@
|
||||
# BTS7960 Motor Controller
|
||||
# Dual BTS7960 Motor Controller
|
||||
|
||||
ESP32-based DC motor controller with web interface, using BTS7960 dual H-bridge driver with current sensing and stall protection.
|
||||
ESP32-based differential drive robot controller with web interface, using two BTS7960 dual H-bridge drivers with current sensing and stall protection.
|
||||
|
||||
## Features
|
||||
|
||||
- Web-based control panel with real-time current monitoring
|
||||
- Forward/Reverse/Stop motor control with speed slider (20-100%)
|
||||
- Current sensing on both H-bridge sides (R_IS and L_IS)
|
||||
- Sample-based stall detection with automatic motor shutoff
|
||||
- Web-based dual motor control panel with real-time current monitoring
|
||||
- Independent Forward/Reverse/Stop control for each motor with speed sliders (20-100%)
|
||||
- Current sensing on both H-bridge sides for each motor
|
||||
- Sample-based stall detection with automatic motor shutoff (per motor)
|
||||
- ADC offset calibration at startup for accurate current readings
|
||||
- Stall warning displayed on web interface
|
||||
- Stall warning displayed on web interface per motor
|
||||
- Emergency stop for both motors
|
||||
|
||||
## Hardware
|
||||
|
||||
@@ -18,9 +19,9 @@ ESP32-based DC motor controller with web interface, using BTS7960 dual H-bridge
|
||||
| Component | Model/Specification |
|
||||
|-----------|---------------------|
|
||||
| Microcontroller | ESP32 LOLIN32 Rev1 |
|
||||
| Motor Driver | BTS7960 Dual H-Bridge Module |
|
||||
| Motor Drivers | 2× BTS7960 Dual H-Bridge Module |
|
||||
| Power Supply | 12V DC |
|
||||
| Sense Resistors | 2× 1kΩ (for current sensing) |
|
||||
| Sense Resistors | 4× 1kΩ (for current sensing) |
|
||||
|
||||
### BTS7960 Module Reference
|
||||
|
||||
@@ -29,16 +30,37 @@ ESP32-based DC motor controller with web interface, using BTS7960 dual H-bridge
|
||||
|
||||
## Wiring
|
||||
|
||||
### Motor Control Pins
|
||||
### Pin Assignments
|
||||
|
||||
| BTS7960 Pin | ESP32 GPIO | Function |
|
||||
|-------------|------------|----------|
|
||||
| RPWM | GPIO25 | Forward PWM |
|
||||
| LPWM | GPIO26 | Reverse PWM |
|
||||
| R_EN | GPIO27 | Right Enable |
|
||||
| L_EN | GPIO14 | Left Enable |
|
||||
| VCC | 3.3V | Logic Power |
|
||||
| GND | GND | Ground |
|
||||
Both drivers share enable pins (they enable/disable together).
|
||||
|
||||
| Function | Motor 1 | Motor 2 | Notes |
|
||||
|----------|---------|---------|-------|
|
||||
| **R_EN** | GPIO 27 | GPIO 27 (shared) | Both drivers enable together |
|
||||
| **L_EN** | GPIO 14 | GPIO 14 (shared) | Both drivers enable together |
|
||||
| **RPWM** | GPIO 25 | GPIO 32 | Forward PWM |
|
||||
| **LPWM** | GPIO 26 | GPIO 33 | Reverse PWM |
|
||||
| **R_IS** | GPIO 34 | GPIO 36 (VP) | Current sense - input only |
|
||||
| **L_IS** | GPIO 35 | GPIO 39 (VN) | Current sense - input only |
|
||||
|
||||
### Wiring Diagram
|
||||
|
||||
```
|
||||
ESP32 LOLIN32 BTS7960 #1 BTS7960 #2
|
||||
-------------- ---------- ----------
|
||||
GPIO 27 (R_EN) ------> R_EN -----------> R_EN
|
||||
GPIO 14 (L_EN) ------> L_EN -----------> L_EN
|
||||
|
||||
GPIO 25 (RPWM) ------> RPWM
|
||||
GPIO 26 (LPWM) ------> LPWM
|
||||
GPIO 34 (R_IS) <------ R_IS
|
||||
GPIO 35 (L_IS) <------ L_IS
|
||||
|
||||
GPIO 32 (RPWM) --------------------> RPWM
|
||||
GPIO 33 (LPWM) --------------------> LPWM
|
||||
GPIO 36 (R_IS) <-------------------- R_IS
|
||||
GPIO 39 (L_IS) <-------------------- L_IS
|
||||
```
|
||||
|
||||
### Current Sensing Circuit
|
||||
|
||||
@@ -47,29 +69,19 @@ The BTS7960 has IS (Current Sense) pins that output current proportional to moto
|
||||
```
|
||||
BTS7960 Module ESP32
|
||||
┌─────────────────┐ ┌──────┐
|
||||
│ │ │ │
|
||||
│ R_IS (pin 7) ─┼──────┬───────┤GPIO34│
|
||||
│ │ │ │ │
|
||||
│ │ [R1] │ │
|
||||
│ R_IS (pin 7) ─┼──────┬───────┤GPIOxx│ (34 for M1, 36 for M2)
|
||||
│ │ [R] │ │
|
||||
│ │ 1kΩ │ │
|
||||
│ │ │ │ │
|
||||
│ GND ─┼──────┴───────┤GND │
|
||||
│ │ │ │
|
||||
│ L_IS (pin 8) ─┼──────┬───────┤GPIO35│
|
||||
│ │ │ │ │
|
||||
│ │ [R2] │ │
|
||||
│ L_IS (pin 8) ─┼──────┬───────┤GPIOxx│ (35 for M1, 39 for M2)
|
||||
│ │ [R] │ │
|
||||
│ │ 1kΩ │ │
|
||||
│ │ │ │ │
|
||||
│ GND ─┼──────┴───────┤GND │
|
||||
└─────────────────┘ └──────┘
|
||||
```
|
||||
|
||||
| Connection | Details |
|
||||
|------------|---------|
|
||||
| R_IS → GPIO34 | Through 1kΩ resistor to GND |
|
||||
| L_IS → GPIO35 | Through 1kΩ resistor to GND |
|
||||
|
||||
**Note:** GPIO34 and GPIO35 are input-only pins on ESP32, ideal for ADC readings.
|
||||
**Note:** GPIO34, 35, 36, 39 are input-only pins on ESP32, ideal for ADC readings.
|
||||
|
||||
### Current Sensing Math
|
||||
|
||||
@@ -116,32 +128,61 @@ Access the control panel at `http://10.81.2.185` (or the IP shown on serial moni
|
||||
|
||||
### Features
|
||||
|
||||
- **Current Display**: Real-time left (L) and right (R) current readings in amps
|
||||
- **Direction Status**: Shows FORWARD, REVERSE, or STOPPED
|
||||
- **Speed Slider**: Adjustable from 20% to 100% (minimum PWM prevents motor stalling at low speeds)
|
||||
- **Stall Warning**: Red banner appears when stall is detected
|
||||
- **Dual Motor Panels**: Side-by-side controls for Motor 1 (Left) and Motor 2 (Right)
|
||||
- **Current Display**: Real-time forward (FWD) and reverse (REV) current readings per motor
|
||||
- **Direction Status**: Shows FORWARD, REVERSE, or STOPPED per motor
|
||||
- **Speed Sliders**: Adjustable from 20% to 100% per motor
|
||||
- **Stall Warning**: Red banner per motor when stall is detected
|
||||
- **Emergency Stop**: Global button to stop both motors immediately
|
||||
|
||||
### API Endpoints
|
||||
|
||||
| Endpoint | Method | Parameters | Description |
|
||||
|----------|--------|------------|-------------|
|
||||
| `/` | GET | - | Control panel HTML page |
|
||||
| `/status` | GET | - | JSON: `{speed, direction, currentR, currentL, stalled}` |
|
||||
| `/speed` | POST | `value` (0-100) | Set motor speed percentage |
|
||||
| `/direction` | POST | `value` (-1, 0, 1) | Set direction (reverse/stop/forward) |
|
||||
| `/stop` | POST | - | Emergency stop |
|
||||
| `/status` | GET | - | JSON with both motors' status |
|
||||
| `/motor1/speed` | GET | `value` (0-100) | Set motor 1 speed percentage |
|
||||
| `/motor1/direction` | GET | `value` (-1, 0, 1) | Set motor 1 direction |
|
||||
| `/motor1/stop` | GET | - | Stop motor 1 |
|
||||
| `/motor2/speed` | GET | `value` (0-100) | Set motor 2 speed percentage |
|
||||
| `/motor2/direction` | GET | `value` (-1, 0, 1) | Set motor 2 direction |
|
||||
| `/motor2/stop` | GET | - | Stop motor 2 |
|
||||
| `/stop` | GET | - | Emergency stop (both motors) |
|
||||
| `/speed` | GET | `value` | Legacy: maps to motor1 |
|
||||
| `/direction` | GET | `value` | Legacy: maps to motor1 |
|
||||
|
||||
### Status JSON Format
|
||||
|
||||
```json
|
||||
{
|
||||
"motor1": {
|
||||
"speed": 50,
|
||||
"direction": 1,
|
||||
"currentR": 2.35,
|
||||
"currentL": 0.00,
|
||||
"stalled": false
|
||||
},
|
||||
"motor2": {
|
||||
"speed": 50,
|
||||
"direction": -1,
|
||||
"currentR": 0.00,
|
||||
"currentL": 1.87,
|
||||
"stalled": false
|
||||
}
|
||||
}
|
||||
```
|
||||
|
||||
## Stall Protection
|
||||
|
||||
The stall detection uses a sample-based approach for reliability:
|
||||
The stall detection uses a sample-based approach for reliability (independent per motor):
|
||||
|
||||
1. **Threshold**: Current above 8.0A indicates potential stall (based on observed ~2A running vs ~17A stalled)
|
||||
2. **Debounce**: 3 consecutive samples above threshold confirms stall (~300ms at 100ms intervals)
|
||||
3. **Stabilization**: Ignores current spikes for 500ms after direction changes
|
||||
|
||||
When stall is confirmed:
|
||||
1. Motor stops immediately
|
||||
2. Serial log: `STALL PROTECTION: Stopping motor (current: X.XXA)`
|
||||
3. Web interface shows red "STALL DETECTED" warning
|
||||
When stall is confirmed on a motor:
|
||||
1. That motor stops immediately
|
||||
2. Serial log: `MotorX STALL DETECTED! Current=X.XXA (threshold=8.0A)`
|
||||
3. Web interface shows red "STALL!" warning on that motor's panel
|
||||
|
||||
To resume operation, send a new direction command via the web interface.
|
||||
|
||||
30
src/main.cpp
30
src/main.cpp
@@ -4,10 +4,16 @@
|
||||
#include "motor.h"
|
||||
#include "webserver.h"
|
||||
|
||||
// Called when motor stall is detected
|
||||
void onMotorStall() {
|
||||
Serial.println("Stall callback triggered - stopping motor!");
|
||||
motor.stop();
|
||||
// Called when motor 1 stall is detected
|
||||
void onMotor1Stall() {
|
||||
Serial.println("Motor1 stall callback triggered - stopping motor!");
|
||||
motor1.stop();
|
||||
}
|
||||
|
||||
// Called when motor 2 stall is detected
|
||||
void onMotor2Stall() {
|
||||
Serial.println("Motor2 stall callback triggered - stopping motor!");
|
||||
motor2.stop();
|
||||
}
|
||||
|
||||
void setupWiFi() {
|
||||
@@ -44,13 +50,16 @@ void setup() {
|
||||
delay(1000);
|
||||
|
||||
Serial.println("\n=============================");
|
||||
Serial.println(" BTS7960 Motor Controller");
|
||||
Serial.println(" Simple Stall Detection");
|
||||
Serial.println(" Dual BTS7960 Motor Controller");
|
||||
Serial.println(" Differential Drive Robot");
|
||||
Serial.println("=============================\n");
|
||||
|
||||
// Initialize motor controller
|
||||
motor.begin();
|
||||
motor.setStallCallback(onMotorStall);
|
||||
// Initialize motor controllers
|
||||
motor1.begin();
|
||||
motor1.setStallCallback(onMotor1Stall);
|
||||
|
||||
motor2.begin();
|
||||
motor2.setStallCallback(onMotor2Stall);
|
||||
|
||||
// Connect to WiFi
|
||||
setupWiFi();
|
||||
@@ -65,6 +74,7 @@ void setup() {
|
||||
|
||||
void loop() {
|
||||
handleWebServer();
|
||||
motor.update(); // Update current sensing and logging
|
||||
motor1.update(); // Update current sensing and logging for motor 1
|
||||
motor2.update(); // Update current sensing and logging for motor 2
|
||||
delay(1);
|
||||
}
|
||||
|
||||
104
src/motor.cpp
104
src/motor.cpp
@@ -6,41 +6,57 @@
|
||||
// Number of samples for offset calibration
|
||||
#define OFFSET_CALIBRATION_SAMPLES 16
|
||||
|
||||
MotorController motor;
|
||||
// Static member initialization
|
||||
bool MotorController::_enablePinsConfigured = false;
|
||||
|
||||
// Create two motor controller instances
|
||||
MotorController motor1(MOTOR1_PINS, "Motor1");
|
||||
MotorController motor2(MOTOR2_PINS, "Motor2");
|
||||
|
||||
// Constructor
|
||||
MotorController::MotorController(const MotorPins& pins, const char* name)
|
||||
: _pins(pins), _name(name) {
|
||||
}
|
||||
|
||||
void MotorController::begin() {
|
||||
// Configure enable pins as outputs
|
||||
pinMode(R_EN_PIN, OUTPUT);
|
||||
pinMode(L_EN_PIN, OUTPUT);
|
||||
// Configure shared enable pins only once (first motor to initialize does this)
|
||||
if (!_enablePinsConfigured) {
|
||||
pinMode(R_EN_PIN, OUTPUT);
|
||||
pinMode(L_EN_PIN, OUTPUT);
|
||||
|
||||
// Enable the H-bridge (shared by both drivers)
|
||||
digitalWrite(R_EN_PIN, HIGH);
|
||||
digitalWrite(L_EN_PIN, HIGH);
|
||||
|
||||
_enablePinsConfigured = true;
|
||||
Serial.println("Shared enable pins configured (HIGH)");
|
||||
}
|
||||
|
||||
// Enable the H-bridge
|
||||
digitalWrite(R_EN_PIN, HIGH);
|
||||
digitalWrite(L_EN_PIN, HIGH);
|
||||
|
||||
// Configure LEDC PWM channels for ESP32
|
||||
ledcSetup(PWM_CHANNEL_R, PWM_FREQ, PWM_RESOLUTION);
|
||||
ledcSetup(PWM_CHANNEL_L, PWM_FREQ, PWM_RESOLUTION);
|
||||
// Configure LEDC PWM channels for this motor
|
||||
ledcSetup(_pins.pwm_channel_r, PWM_FREQ, PWM_RESOLUTION);
|
||||
ledcSetup(_pins.pwm_channel_l, PWM_FREQ, PWM_RESOLUTION);
|
||||
|
||||
// Attach PWM channels to GPIO pins
|
||||
ledcAttachPin(RPWM_PIN, PWM_CHANNEL_R);
|
||||
ledcAttachPin(LPWM_PIN, PWM_CHANNEL_L);
|
||||
ledcAttachPin(_pins.rpwm, _pins.pwm_channel_r);
|
||||
ledcAttachPin(_pins.lpwm, _pins.pwm_channel_l);
|
||||
|
||||
#if CURRENT_SENSING_ENABLED
|
||||
// Configure current sense pins as analog inputs
|
||||
// GPIO34 and GPIO35 are input-only pins, perfect for ADC
|
||||
// GPIO34, 35, 36, 39 are input-only pins, perfect for ADC
|
||||
analogSetAttenuation(ADC_11db); // Full range 0-3.3V
|
||||
pinMode(R_IS_PIN, INPUT);
|
||||
pinMode(L_IS_PIN, INPUT);
|
||||
pinMode(_pins.r_is, INPUT);
|
||||
pinMode(_pins.l_is, INPUT);
|
||||
|
||||
// Calibrate zero-current offset (ESP32 ADC has inherent offset)
|
||||
calibrateCurrentOffset();
|
||||
Serial.println("Current sensing enabled");
|
||||
Serial.printf("%s: Current sensing enabled\n", _name);
|
||||
#endif
|
||||
|
||||
// Start stopped
|
||||
stop();
|
||||
|
||||
Serial.println("Motor controller initialized");
|
||||
Serial.printf("%s: Controller initialized (RPWM=%d, LPWM=%d)\n",
|
||||
_name, _pins.rpwm, _pins.lpwm);
|
||||
}
|
||||
|
||||
void MotorController::setSpeed(int speed) {
|
||||
@@ -61,10 +77,10 @@ void MotorController::setDirection(int dir) {
|
||||
void MotorController::stop() {
|
||||
// Don't reset _speed - keep last speed setting
|
||||
_direction = 0;
|
||||
ledcWrite(PWM_CHANNEL_R, 0);
|
||||
ledcWrite(PWM_CHANNEL_L, 0);
|
||||
ledcWrite(_pins.pwm_channel_r, 0);
|
||||
ledcWrite(_pins.pwm_channel_l, 0);
|
||||
resetStallDetection();
|
||||
Serial.println("Motor: STOPPED (manual)");
|
||||
Serial.printf("%s: STOPPED (manual)\n", _name);
|
||||
}
|
||||
|
||||
void MotorController::update() {
|
||||
@@ -76,8 +92,8 @@ void MotorController::update() {
|
||||
const int dotInterval = 5; // Print dot every N idle readings
|
||||
|
||||
// Read current sensors
|
||||
_currentRight = readCurrentSense(R_IS_PIN);
|
||||
_currentLeft = readCurrentSense(L_IS_PIN);
|
||||
_currentRight = readCurrentSense(_pins.r_is);
|
||||
_currentLeft = readCurrentSense(_pins.l_is);
|
||||
|
||||
// Log current readings frequently for data collection
|
||||
unsigned long now = millis();
|
||||
@@ -90,8 +106,8 @@ void MotorController::update() {
|
||||
if (isIdle) {
|
||||
if (!lastWasIdle) {
|
||||
// First idle after non-idle: print full line once
|
||||
Serial.printf("CURRENT: R=%.2fA L=%.2fA dir=%d spd=%d\n",
|
||||
_currentRight, _currentLeft, _direction, _speed);
|
||||
Serial.printf("%s CURRENT: R=%.2fA L=%.2fA dir=%d spd=%d\n",
|
||||
_name, _currentRight, _currentLeft, _direction, _speed);
|
||||
idleDotCount = 0;
|
||||
} else {
|
||||
// Subsequent idle: print dot every N readings
|
||||
@@ -109,8 +125,8 @@ void MotorController::update() {
|
||||
if (lastWasIdle && idleDotCount > 0) {
|
||||
Serial.println(); // Newline after dots before full reading
|
||||
}
|
||||
Serial.printf("CURRENT: R=%.2fA L=%.2fA dir=%d spd=%d\n",
|
||||
_currentRight, _currentLeft, _direction, _speed);
|
||||
Serial.printf("%s CURRENT: R=%.2fA L=%.2fA dir=%d spd=%d\n",
|
||||
_name, _currentRight, _currentLeft, _direction, _speed);
|
||||
lastWasIdle = false;
|
||||
idleDotCount = 0;
|
||||
}
|
||||
@@ -146,6 +162,10 @@ float MotorController::getCurrentActive() {
|
||||
return 0.0f;
|
||||
}
|
||||
|
||||
const char* MotorController::getName() {
|
||||
return _name;
|
||||
}
|
||||
|
||||
// Stall detection
|
||||
bool MotorController::isStalled() {
|
||||
return _stalled;
|
||||
@@ -181,8 +201,8 @@ void MotorController::checkStall() {
|
||||
|
||||
if (_stallConfirmCount >= STALL_CONFIRM_SAMPLES && !_stalled) {
|
||||
_stalled = true;
|
||||
Serial.printf("STALL DETECTED! Current=%.2fA (threshold=%.1fA)\n",
|
||||
activeCurrent, STALL_THRESHOLD);
|
||||
Serial.printf("%s STALL DETECTED! Current=%.2fA (threshold=%.1fA)\n",
|
||||
_name, activeCurrent, STALL_THRESHOLD);
|
||||
|
||||
// Call stall callback if registered
|
||||
if (_stallCallback != nullptr) {
|
||||
@@ -196,7 +216,7 @@ void MotorController::checkStall() {
|
||||
// Clear stall flag if current returns to normal
|
||||
if (_stalled) {
|
||||
_stalled = false;
|
||||
Serial.println("Stall condition cleared");
|
||||
Serial.printf("%s: Stall condition cleared\n", _name);
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -213,19 +233,19 @@ void MotorController::applyMotorState() {
|
||||
|
||||
if (_direction == 0 || _speed == 0) {
|
||||
// Stop - both PWM outputs off
|
||||
ledcWrite(PWM_CHANNEL_R, 0);
|
||||
ledcWrite(PWM_CHANNEL_L, 0);
|
||||
ledcWrite(_pins.pwm_channel_r, 0);
|
||||
ledcWrite(_pins.pwm_channel_l, 0);
|
||||
} else if (_direction > 0) {
|
||||
// Forward - RPWM active, LPWM off
|
||||
ledcWrite(PWM_CHANNEL_R, pwmValue);
|
||||
ledcWrite(PWM_CHANNEL_L, 0);
|
||||
ledcWrite(_pins.pwm_channel_r, pwmValue);
|
||||
ledcWrite(_pins.pwm_channel_l, 0);
|
||||
} else {
|
||||
// Reverse - LPWM active, RPWM off
|
||||
ledcWrite(PWM_CHANNEL_R, 0);
|
||||
ledcWrite(PWM_CHANNEL_L, pwmValue);
|
||||
ledcWrite(_pins.pwm_channel_r, 0);
|
||||
ledcWrite(_pins.pwm_channel_l, pwmValue);
|
||||
}
|
||||
|
||||
Serial.printf("Motor: dir=%d, speed=%d%%, pwm=%d\n", _direction, _speed, pwmValue);
|
||||
Serial.printf("%s: dir=%d, speed=%d%%, pwm=%d\n", _name, _direction, _speed, pwmValue);
|
||||
}
|
||||
|
||||
float MotorController::readCurrentSense(int pin) {
|
||||
@@ -234,7 +254,7 @@ float MotorController::readCurrentSense(int pin) {
|
||||
int adcValue = analogRead(pin);
|
||||
|
||||
// Subtract zero-current offset (calibrated at startup)
|
||||
int offset = (pin == R_IS_PIN) ? _adcOffsetRight : _adcOffsetLeft;
|
||||
int offset = (pin == _pins.r_is) ? _adcOffsetRight : _adcOffsetLeft;
|
||||
adcValue = adcValue - offset;
|
||||
if (adcValue < 0) adcValue = 0; // Clamp to zero
|
||||
|
||||
@@ -263,15 +283,15 @@ void MotorController::calibrateCurrentOffset() {
|
||||
long sumLeft = 0;
|
||||
|
||||
for (int i = 0; i < OFFSET_CALIBRATION_SAMPLES; i++) {
|
||||
sumRight += analogRead(R_IS_PIN);
|
||||
sumLeft += analogRead(L_IS_PIN);
|
||||
sumRight += analogRead(_pins.r_is);
|
||||
sumLeft += analogRead(_pins.l_is);
|
||||
delay(5); // Small delay between samples
|
||||
}
|
||||
|
||||
_adcOffsetRight = sumRight / OFFSET_CALIBRATION_SAMPLES;
|
||||
_adcOffsetLeft = sumLeft / OFFSET_CALIBRATION_SAMPLES;
|
||||
|
||||
Serial.printf("Current sense offset calibrated: R=%d L=%d (ADC counts)\n",
|
||||
_adcOffsetRight, _adcOffsetLeft);
|
||||
Serial.printf("%s: Current sense offset calibrated: R=%d L=%d (ADC counts)\n",
|
||||
_name, _adcOffsetRight, _adcOffsetLeft);
|
||||
#endif
|
||||
}
|
||||
|
||||
@@ -5,13 +5,13 @@
|
||||
|
||||
WebServer server(HTTP_PORT);
|
||||
|
||||
// HTML page for motor control
|
||||
// HTML page for dual motor control
|
||||
const char index_html[] PROGMEM = R"rawliteral(
|
||||
<!DOCTYPE html>
|
||||
<html>
|
||||
<head>
|
||||
<meta name="viewport" content="width=device-width, initial-scale=1">
|
||||
<title>Motor Control</title>
|
||||
<title>Dual Motor Control</title>
|
||||
<style>
|
||||
* { box-sizing: border-box; }
|
||||
body {
|
||||
@@ -23,34 +23,40 @@ const char index_html[] PROGMEM = R"rawliteral(
|
||||
min-height: 100vh;
|
||||
}
|
||||
.container {
|
||||
max-width: 400px;
|
||||
max-width: 800px;
|
||||
margin: 0 auto;
|
||||
text-align: center;
|
||||
}
|
||||
h1 { color: #00d9ff; margin-bottom: 30px; }
|
||||
h2 { color: #00d9ff; margin: 20px 0 15px 0; font-size: 20px; }
|
||||
.status {
|
||||
h2 { color: #00d9ff; margin: 10px 0; font-size: 20px; }
|
||||
.motors-container {
|
||||
display: grid;
|
||||
grid-template-columns: 1fr 1fr;
|
||||
gap: 20px;
|
||||
}
|
||||
@media (max-width: 600px) {
|
||||
.motors-container {
|
||||
grid-template-columns: 1fr;
|
||||
}
|
||||
}
|
||||
.motor-panel {
|
||||
background: #16213e;
|
||||
padding: 15px;
|
||||
border-radius: 10px;
|
||||
margin-bottom: 20px;
|
||||
padding: 20px;
|
||||
border-radius: 15px;
|
||||
}
|
||||
.status span {
|
||||
font-size: 24px;
|
||||
font-size: 20px;
|
||||
font-weight: bold;
|
||||
color: #00d9ff;
|
||||
}
|
||||
.current-display {
|
||||
background: #16213e;
|
||||
padding: 15px;
|
||||
border-radius: 10px;
|
||||
margin-bottom: 20px;
|
||||
display: grid;
|
||||
grid-template-columns: 1fr 1fr;
|
||||
gap: 10px;
|
||||
margin: 15px 0;
|
||||
}
|
||||
.current-value {
|
||||
font-size: 28px;
|
||||
font-size: 24px;
|
||||
font-weight: bold;
|
||||
color: #00d9ff;
|
||||
}
|
||||
@@ -59,41 +65,38 @@ const char index_html[] PROGMEM = R"rawliteral(
|
||||
color: #888;
|
||||
}
|
||||
.slider-container {
|
||||
background: #16213e;
|
||||
padding: 20px;
|
||||
border-radius: 10px;
|
||||
margin-bottom: 20px;
|
||||
margin: 15px 0;
|
||||
}
|
||||
.slider {
|
||||
width: 100%;
|
||||
height: 25px;
|
||||
height: 20px;
|
||||
-webkit-appearance: none;
|
||||
background: #0f3460;
|
||||
border-radius: 12px;
|
||||
border-radius: 10px;
|
||||
outline: none;
|
||||
}
|
||||
.slider::-webkit-slider-thumb {
|
||||
-webkit-appearance: none;
|
||||
width: 35px;
|
||||
height: 35px;
|
||||
width: 30px;
|
||||
height: 30px;
|
||||
background: #00d9ff;
|
||||
border-radius: 50%;
|
||||
cursor: pointer;
|
||||
}
|
||||
.buttons {
|
||||
display: flex;
|
||||
gap: 10px;
|
||||
gap: 8px;
|
||||
justify-content: center;
|
||||
flex-wrap: wrap;
|
||||
}
|
||||
.btn {
|
||||
padding: 20px 30px;
|
||||
font-size: 18px;
|
||||
padding: 15px 20px;
|
||||
font-size: 14px;
|
||||
border: none;
|
||||
border-radius: 10px;
|
||||
border-radius: 8px;
|
||||
cursor: pointer;
|
||||
transition: transform 0.1s, background 0.2s;
|
||||
min-width: 100px;
|
||||
min-width: 80px;
|
||||
}
|
||||
.btn:active { transform: scale(0.95); }
|
||||
.btn-forward { background: #00c853; color: white; }
|
||||
@@ -101,124 +104,187 @@ const char index_html[] PROGMEM = R"rawliteral(
|
||||
.btn-stop { background: #ff9100; color: white; flex-basis: 100%; }
|
||||
.btn:hover { filter: brightness(1.1); }
|
||||
.speed-value {
|
||||
font-size: 48px;
|
||||
font-size: 36px;
|
||||
color: #00d9ff;
|
||||
margin: 10px 0;
|
||||
}
|
||||
.section-divider {
|
||||
border-top: 2px solid #0f3460;
|
||||
margin: 30px 0;
|
||||
margin: 5px 0;
|
||||
}
|
||||
.stall-warning {
|
||||
background: #ff5252;
|
||||
color: white;
|
||||
padding: 15px;
|
||||
border-radius: 10px;
|
||||
margin-bottom: 20px;
|
||||
padding: 10px;
|
||||
border-radius: 8px;
|
||||
margin-bottom: 15px;
|
||||
font-weight: bold;
|
||||
font-size: 18px;
|
||||
display: none;
|
||||
}
|
||||
.stall-warning.active {
|
||||
display: block;
|
||||
}
|
||||
.global-controls {
|
||||
margin-top: 20px;
|
||||
padding: 20px;
|
||||
background: #0f3460;
|
||||
border-radius: 15px;
|
||||
}
|
||||
.global-controls h2 {
|
||||
margin-top: 0;
|
||||
}
|
||||
.btn-emergency {
|
||||
background: #d50000;
|
||||
color: white;
|
||||
font-size: 18px;
|
||||
padding: 20px 40px;
|
||||
}
|
||||
</style>
|
||||
</head>
|
||||
<body>
|
||||
<div class="container">
|
||||
<h1>Motor Control</h1>
|
||||
<h1>Dual Motor Control</h1>
|
||||
|
||||
<div class="stall-warning" id="stallWarning">⚠️ STALL DETECTED!</div>
|
||||
|
||||
<div class="current-display">
|
||||
<div>
|
||||
<div class="current-label">CURRENT R</div>
|
||||
<div class="current-value"><span id="currentR">0.00</span>A</div>
|
||||
<div class="motors-container">
|
||||
<!-- Motor 1 Panel -->
|
||||
<div class="motor-panel">
|
||||
<h2>Motor 1 (Left)</h2>
|
||||
<div class="stall-warning" id="stallWarning1">⚠️ STALL!</div>
|
||||
|
||||
<div class="current-display">
|
||||
<div>
|
||||
<div class="current-label">FWD</div>
|
||||
<div class="current-value"><span id="m1_currentR">0.00</span>A</div>
|
||||
</div>
|
||||
<div>
|
||||
<div class="current-label">REV</div>
|
||||
<div class="current-value"><span id="m1_currentL">0.00</span>A</div>
|
||||
</div>
|
||||
</div>
|
||||
|
||||
<div class="status">
|
||||
<span id="m1_dirStatus">STOPPED</span>
|
||||
</div>
|
||||
|
||||
<div class="slider-container">
|
||||
<div class="speed-value"><span id="m1_speedValue">20</span>%</div>
|
||||
<input type="range" class="slider" id="m1_slider" min="20" max="100" value="20">
|
||||
</div>
|
||||
|
||||
<div class="buttons">
|
||||
<button class="btn btn-forward" onclick="setDir(1, 1)">FWD</button>
|
||||
<button class="btn btn-reverse" onclick="setDir(1, -1)">REV</button>
|
||||
<button class="btn btn-stop" onclick="stopMotor(1)">STOP</button>
|
||||
</div>
|
||||
</div>
|
||||
<div>
|
||||
<div class="current-label">CURRENT L</div>
|
||||
<div class="current-value"><span id="currentL">0.00</span>A</div>
|
||||
|
||||
<!-- Motor 2 Panel -->
|
||||
<div class="motor-panel">
|
||||
<h2>Motor 2 (Right)</h2>
|
||||
<div class="stall-warning" id="stallWarning2">⚠️ STALL!</div>
|
||||
|
||||
<div class="current-display">
|
||||
<div>
|
||||
<div class="current-label">FWD</div>
|
||||
<div class="current-value"><span id="m2_currentR">0.00</span>A</div>
|
||||
</div>
|
||||
<div>
|
||||
<div class="current-label">REV</div>
|
||||
<div class="current-value"><span id="m2_currentL">0.00</span>A</div>
|
||||
</div>
|
||||
</div>
|
||||
|
||||
<div class="status">
|
||||
<span id="m2_dirStatus">STOPPED</span>
|
||||
</div>
|
||||
|
||||
<div class="slider-container">
|
||||
<div class="speed-value"><span id="m2_speedValue">20</span>%</div>
|
||||
<input type="range" class="slider" id="m2_slider" min="20" max="100" value="20">
|
||||
</div>
|
||||
|
||||
<div class="buttons">
|
||||
<button class="btn btn-forward" onclick="setDir(2, 1)">FWD</button>
|
||||
<button class="btn btn-reverse" onclick="setDir(2, -1)">REV</button>
|
||||
<button class="btn btn-stop" onclick="stopMotor(2)">STOP</button>
|
||||
</div>
|
||||
</div>
|
||||
</div>
|
||||
|
||||
<div class="status">
|
||||
Direction: <span id="dirStatus">STOPPED</span>
|
||||
</div>
|
||||
|
||||
<div class="slider-container">
|
||||
<label>Speed</label>
|
||||
<div class="speed-value"><span id="speedValue">20</span>%</div>
|
||||
<input type="range" class="slider" id="speedSlider" min="20" max="100" value="20">
|
||||
</div>
|
||||
|
||||
<div class="buttons">
|
||||
<button class="btn btn-forward" onclick="setDir(1)">FORWARD</button>
|
||||
<button class="btn btn-reverse" onclick="setDir(-1)">REVERSE</button>
|
||||
<button class="btn btn-stop" onclick="stopMotor()">STOP</button>
|
||||
<div class="global-controls">
|
||||
<h2>Global Controls</h2>
|
||||
<button class="btn btn-emergency" onclick="emergencyStop()">⛔ EMERGENCY STOP</button>
|
||||
</div>
|
||||
</div>
|
||||
|
||||
<script>
|
||||
const slider = document.getElementById('speedSlider');
|
||||
const speedVal = document.getElementById('speedValue');
|
||||
const dirStatus = document.getElementById('dirStatus');
|
||||
let currentDir = 0;
|
||||
|
||||
slider.oninput = function() {
|
||||
speedVal.textContent = this.value;
|
||||
// Motor state
|
||||
const motors = {
|
||||
1: { slider: document.getElementById('m1_slider'), speedVal: document.getElementById('m1_speedValue'),
|
||||
dirStatus: document.getElementById('m1_dirStatus'), dir: 0 },
|
||||
2: { slider: document.getElementById('m2_slider'), speedVal: document.getElementById('m2_speedValue'),
|
||||
dirStatus: document.getElementById('m2_dirStatus'), dir: 0 }
|
||||
};
|
||||
|
||||
slider.onchange = function() {
|
||||
fetch('/speed?value=' + this.value)
|
||||
.then(r => r.text())
|
||||
.then(console.log);
|
||||
};
|
||||
|
||||
function setDir(dir) {
|
||||
currentDir = dir;
|
||||
fetch('/direction?value=' + dir)
|
||||
.then(r => r.text())
|
||||
.then(() => updateStatus());
|
||||
// Slider events
|
||||
for (let m of [1, 2]) {
|
||||
motors[m].slider.oninput = function() {
|
||||
motors[m].speedVal.textContent = this.value;
|
||||
};
|
||||
motors[m].slider.onchange = function() {
|
||||
fetch('/motor' + m + '/speed?value=' + this.value);
|
||||
};
|
||||
}
|
||||
|
||||
function stopMotor() {
|
||||
currentDir = 0;
|
||||
// Don't reset slider - keep last speed
|
||||
fetch('/stop')
|
||||
.then(r => r.text())
|
||||
.then(() => updateStatus());
|
||||
function setDir(motor, dir) {
|
||||
motors[motor].dir = dir;
|
||||
fetch('/motor' + motor + '/direction?value=' + dir)
|
||||
.then(() => updateStatus(motor));
|
||||
}
|
||||
|
||||
function updateStatus() {
|
||||
if (currentDir > 0) dirStatus.textContent = 'FORWARD';
|
||||
else if (currentDir < 0) dirStatus.textContent = 'REVERSE';
|
||||
else dirStatus.textContent = 'STOPPED';
|
||||
function stopMotor(motor) {
|
||||
motors[motor].dir = 0;
|
||||
fetch('/motor' + motor + '/stop')
|
||||
.then(() => updateStatus(motor));
|
||||
}
|
||||
|
||||
function emergencyStop() {
|
||||
fetch('/stop').then(() => {
|
||||
motors[1].dir = 0;
|
||||
motors[2].dir = 0;
|
||||
updateStatus(1);
|
||||
updateStatus(2);
|
||||
});
|
||||
}
|
||||
|
||||
function updateStatus(motor) {
|
||||
const m = motors[motor];
|
||||
if (m.dir > 0) m.dirStatus.textContent = 'FORWARD';
|
||||
else if (m.dir < 0) m.dirStatus.textContent = 'REVERSE';
|
||||
else m.dirStatus.textContent = 'STOPPED';
|
||||
}
|
||||
|
||||
function pollStatus() {
|
||||
fetch('/status')
|
||||
.then(r => r.json())
|
||||
.then(data => {
|
||||
// Only update speed display if motor is running (direction != 0)
|
||||
// When stopped, keep the last speed setting
|
||||
if (data.direction != 0) {
|
||||
slider.value = data.speed;
|
||||
speedVal.textContent = data.speed;
|
||||
// Update Motor 1
|
||||
if (data.motor1.direction != 0) {
|
||||
motors[1].slider.value = data.motor1.speed;
|
||||
motors[1].speedVal.textContent = data.motor1.speed;
|
||||
}
|
||||
currentDir = data.direction;
|
||||
updateStatus();
|
||||
motors[1].dir = data.motor1.direction;
|
||||
updateStatus(1);
|
||||
document.getElementById('m1_currentR').textContent = data.motor1.currentR.toFixed(2);
|
||||
document.getElementById('m1_currentL').textContent = data.motor1.currentL.toFixed(2);
|
||||
document.getElementById('stallWarning1').classList.toggle('active', data.motor1.stalled);
|
||||
|
||||
// Update current display
|
||||
document.getElementById('currentR').textContent = data.currentR.toFixed(2);
|
||||
document.getElementById('currentL').textContent = data.currentL.toFixed(2);
|
||||
|
||||
// Update stall warning
|
||||
const stallWarning = document.getElementById('stallWarning');
|
||||
if (data.stalled) {
|
||||
stallWarning.classList.add('active');
|
||||
} else {
|
||||
stallWarning.classList.remove('active');
|
||||
// Update Motor 2
|
||||
if (data.motor2.direction != 0) {
|
||||
motors[2].slider.value = data.motor2.speed;
|
||||
motors[2].speedVal.textContent = data.motor2.speed;
|
||||
}
|
||||
motors[2].dir = data.motor2.direction;
|
||||
updateStatus(2);
|
||||
document.getElementById('m2_currentR').textContent = data.motor2.currentR.toFixed(2);
|
||||
document.getElementById('m2_currentL').textContent = data.motor2.currentL.toFixed(2);
|
||||
document.getElementById('stallWarning2').classList.toggle('active', data.motor2.stalled);
|
||||
});
|
||||
}
|
||||
|
||||
@@ -234,45 +300,119 @@ void handleRoot() {
|
||||
server.send(200, "text/html", index_html);
|
||||
}
|
||||
|
||||
void handleSpeed() {
|
||||
// Motor 1 handlers
|
||||
void handleMotor1Speed() {
|
||||
if (server.hasArg("value")) {
|
||||
int speed = server.arg("value").toInt();
|
||||
motor.setSpeed(speed);
|
||||
motor1.setSpeed(speed);
|
||||
server.send(200, "text/plain", "OK");
|
||||
} else {
|
||||
server.send(400, "text/plain", "Missing value");
|
||||
}
|
||||
}
|
||||
|
||||
void handleDirection() {
|
||||
void handleMotor1Direction() {
|
||||
if (server.hasArg("value")) {
|
||||
int dir = server.arg("value").toInt();
|
||||
motor.setDirection(dir);
|
||||
motor1.setDirection(dir);
|
||||
server.send(200, "text/plain", "OK");
|
||||
} else {
|
||||
server.send(400, "text/plain", "Missing value");
|
||||
}
|
||||
}
|
||||
|
||||
void handleStop() {
|
||||
motor.stop();
|
||||
void handleMotor1Stop() {
|
||||
motor1.stop();
|
||||
server.send(200, "text/plain", "OK");
|
||||
}
|
||||
|
||||
// Motor 2 handlers
|
||||
void handleMotor2Speed() {
|
||||
if (server.hasArg("value")) {
|
||||
int speed = server.arg("value").toInt();
|
||||
motor2.setSpeed(speed);
|
||||
server.send(200, "text/plain", "OK");
|
||||
} else {
|
||||
server.send(400, "text/plain", "Missing value");
|
||||
}
|
||||
}
|
||||
|
||||
void handleMotor2Direction() {
|
||||
if (server.hasArg("value")) {
|
||||
int dir = server.arg("value").toInt();
|
||||
motor2.setDirection(dir);
|
||||
server.send(200, "text/plain", "OK");
|
||||
} else {
|
||||
server.send(400, "text/plain", "Missing value");
|
||||
}
|
||||
}
|
||||
|
||||
void handleMotor2Stop() {
|
||||
motor2.stop();
|
||||
server.send(200, "text/plain", "OK");
|
||||
}
|
||||
|
||||
// Global stop (emergency stop both motors)
|
||||
void handleStop() {
|
||||
motor1.stop();
|
||||
motor2.stop();
|
||||
server.send(200, "text/plain", "OK");
|
||||
}
|
||||
|
||||
// Legacy handlers (map to motor1 for backwards compatibility)
|
||||
void handleSpeed() {
|
||||
handleMotor1Speed();
|
||||
}
|
||||
|
||||
void handleDirection() {
|
||||
handleMotor1Direction();
|
||||
}
|
||||
|
||||
// Status handler - returns both motors' data
|
||||
void handleStatus() {
|
||||
String json = "{\"speed\":" + String(motor.getSpeed()) +
|
||||
",\"direction\":" + String(motor.getDirection()) +
|
||||
",\"currentR\":" + String(motor.getCurrentRight(), 2) +
|
||||
",\"currentL\":" + String(motor.getCurrentLeft(), 2) +
|
||||
",\"stalled\":" + (motor.isStalled() ? "true" : "false") + "}";
|
||||
String json = "{";
|
||||
|
||||
// Motor 1 status
|
||||
json += "\"motor1\":{";
|
||||
json += "\"speed\":" + String(motor1.getSpeed()) + ",";
|
||||
json += "\"direction\":" + String(motor1.getDirection()) + ",";
|
||||
json += "\"currentR\":" + String(motor1.getCurrentRight(), 2) + ",";
|
||||
json += "\"currentL\":" + String(motor1.getCurrentLeft(), 2) + ",";
|
||||
json += "\"stalled\":" + String(motor1.isStalled() ? "true" : "false");
|
||||
json += "},";
|
||||
|
||||
// Motor 2 status
|
||||
json += "\"motor2\":{";
|
||||
json += "\"speed\":" + String(motor2.getSpeed()) + ",";
|
||||
json += "\"direction\":" + String(motor2.getDirection()) + ",";
|
||||
json += "\"currentR\":" + String(motor2.getCurrentRight(), 2) + ",";
|
||||
json += "\"currentL\":" + String(motor2.getCurrentLeft(), 2) + ",";
|
||||
json += "\"stalled\":" + String(motor2.isStalled() ? "true" : "false");
|
||||
json += "}";
|
||||
|
||||
json += "}";
|
||||
server.send(200, "application/json", json);
|
||||
}
|
||||
|
||||
void setupWebServer() {
|
||||
server.on("/", handleRoot);
|
||||
|
||||
// Motor 1 endpoints
|
||||
server.on("/motor1/speed", handleMotor1Speed);
|
||||
server.on("/motor1/direction", handleMotor1Direction);
|
||||
server.on("/motor1/stop", handleMotor1Stop);
|
||||
|
||||
// Motor 2 endpoints
|
||||
server.on("/motor2/speed", handleMotor2Speed);
|
||||
server.on("/motor2/direction", handleMotor2Direction);
|
||||
server.on("/motor2/stop", handleMotor2Stop);
|
||||
|
||||
// Legacy endpoints (backwards compatibility - map to motor1)
|
||||
server.on("/speed", handleSpeed);
|
||||
server.on("/direction", handleDirection);
|
||||
server.on("/stop", handleStop);
|
||||
|
||||
// Global endpoints
|
||||
server.on("/stop", handleStop); // Emergency stop both motors
|
||||
server.on("/status", handleStatus);
|
||||
|
||||
server.begin();
|
||||
|
||||
Reference in New Issue
Block a user