Red Robot Ant
Robot Ant with enhanced gait, RC cam and head sensors.
Ants are fascinating animals. Their individual abilities are amazing, but their community is unique and allows them to realise large projects. Maybe one day I'll manage to connect several robot ants via wifi and have them co-operate.
As in my previous ant projects, I tried to further develop the locomotion. Blue Ant had only 3 servos (+ 1 for the mouth), very economical, but with a rather modest gait. Green Ant already had 12 servos and moved rather realistically, but I struggled with the power supply.
Red Ant is now supposed to be a mixture, fewer servos than green, better gait than blue.
Blue Ant had a servo for each pair of legs, Red Ant gets one servo for each leg, whereby the middle legs do not move forwards and backwards, but only up and down to control the ground grip of the front and rear legs.
Supplies
6 servos MG90
ESP32-S3 (with camera)
or another ESP32 or ESP8266
7.4V LiPo battery (500mAh) *
5V buck converter, adjustable for 5V (~1.20 €)
2 micro switches / buttons (optional)
power switch
PCB
3D printer
helpful:
hot glue or superglue
servo tester
soldering iron
some screws
- LiPo quick charger for S2 and S3 plugs (~ 16 €)
Print the Parts
You need:
- contruction plate (1x)
- front/rear legs (4x)
- big plates (4x)
- small plates (4x)
- servo brackets f+r (4x)
- left mid leg (1x)
- right mid leg (1x)
- left mid bracket (1x)
- right mid bracket (1x)
- mid servo brackets (2x)
- head sensor left (1x)
- head sensor right (1x)
Reset All Servos
Set all servos to position "90". (It is the center of 0-180°).
Use a servo tester for it or e.g. an Arduino.
Insert the Mid Servos
First insert the two mid servos into the construction plate. Use one piece of 2mm wire as a retaining bolt, fix servo and bolt with super glue.
Put the mid bracket and mid leg parts together and secure them with glue. Place a lever arm on the servo, attach the bracket and secure the servo gear with a screw. We also drill a small hole through the bracket and servo arm to secure it with a small screw.
Insert the Front and Rear Servos
Insert the two front servos and the two rear servos into the construction plate as seen in the pictures. Fix each servo with one or two of the supplied screws. Place a lever arm at a right angle on each servo.
Attach the Legs
Fix one upper big plate to the servo arm and fix it with a screw. Glue the servo brackets to the lower side of the servos. Fix the legs on the big and the small plaste as seen in the picture. Fix plates and leg with superglue. Small plate and bracket must not be fixed!
Wiring and PCB
The 7.7V current is modified by an adjustable buck converter to 5V. Here we connect the servos and the ESP32 to the power supply. I used a little PCB with pins to connect (image). First separate the data cable (orange) of the servos. They should be connected to the ESP32 in the head later. Usually the wires of the servos are long enough. The current pins are connected to the selfmade pin board in the rear body part together with the battery.
It could be useful to insert a power switch. Install it at a suitable position (Step 7).
Tail for the Battery
The tail is fixed to the mid body part by a screw. In this tail is enough space for battery, PCB and cables.
If you have not already done so, you can now connect the battery and the servos and install the switch.
Head and Antennas
Mount the head with a screw. Now you have space for the ESP32-S3.
If you don't want sensors go ahead with the next step.
Solder some wires to the micro switches as seen in the picture, you can use the same GND wire for both switches. Insert the switches in the upper head part, fix them with hot glue.
After the head has been closed, you can connect the sensors to the switch levers.
Prepare the Microcontroller
The ESP32-S3 is surprisingly small and can be programmed with Arduino IDE. You can find help here:
https://www.instructables.com/Getting-Started-With-ESP32-C3-XIAO/
or here at github.
I struggled a long time to install the right servo library. I always got error messages.
The solution was:
1. Do not add only this to Arduino's board manager (File --> Preferences --> Additional board manager URL's)
https://raw.githubusercontent.com/espressif/arduino-esp32/gh-pages/package_esp32_index.json
but also this line:
https://raw.githubusercontent.com/espressif/arduino-esp32/gh-pages/package_esp32_dev_index.json
2. Board manager: ESP32, use Version 2.x. Version 3 is producing error messages with the servo libraries.
Resist when your Arduino ID prompts you to update the board information!
The Walk Program
The two front and two rear legs are the actual movement makers. The middle pair of legs is only used to bring the friction of the other legs to the ground. This is not quite the same as with a real insect, but saves servos and therefore energy.
The program mainly consists of a part for the video streaming and the remote control. The servo movements are divided into sub-programm and are called up by the remote control.
The sketch is transferred to the ESP32: Open the sketch in Arduino IDE on your PC.
Press the tiny boot button on the ESP32-S3 and keep it pressed, then connect the microcontroler and the PC via USB. then click the upload button of Arduino IDE. Then you can release the ESP32 boot button and the transfer will start.
/*
* ESP32S3 XIAO * ESP32S3 XIAO Red Ant Remote Control - Home Web
* make sure that PSRAM is enabled
*
* Markus Opitz 2024 instructables.com
*/
// servos * * * * * * * * * * * * * * * * * * * *
#include <s3servo.h>
s3servo servo1;
s3servo servo2;
s3servo servo3;
s3servo servo4;
s3servo servo5;
s3servo servo6;
int center1 = 75; //best center position of each leg (individual)
//int center2 = 105;
int center2 = 125;
int center3 = 90;
int center4 = 90;
int center5 = 115;
int center6 = 75;
int pos = 90;
int pos2;
int Min = 50; //move betwenn this two values
int Max = 100;
int speed1 = 200; //pause between forward and backward movement
int steplength = 30; //big step
int smallstep = 5; //small step
int flag = 0;
// button * * * * * * * * * * * * * * * * * * * *
const int buttonLeft = 3;
const int buttonRight = 4;
int leftState = 1;
int rightState = 1;
// camera * * * * * * * * * * * * * * * * * * * *
#include "esp_camera.h"
#include <WiFi.h>
#include "esp_timer.h"
#include "img_converters.h"
#include "Arduino.h"
#include "fb_gfx.h"
#include "soc/soc.h" // disable brownout problems
#include "soc/rtc_cntl_reg.h" // disable brownout problems
#include "esp_http_server.h"
#include "esp_http_server.h"
#include "esp32-hal-ledc.h"
#include "sdkconfig.h"
#define CAMERA_MODEL_XIAO_ESP32S3 // Has PSRAM
#if defined(ARDUINO_ARCH_ESP32) && defined(CONFIG_ARDUHAL_ESP_LOG)
#include "esp32-hal-log.h"
#endif
// Replace with your network data * * * * * * * * * * * * * * * * * * * * *
const char* ssid = "********";
const char* password = "********";
#define PART_BOUNDARY "123456789000000000000987654321"
#define CAMERA_MODEL_AI_THINKER
//#define CAMERA_MODEL_WROVER_KIT
#if defined(CAMERA_MODEL_XIAO_ESP32S3)
#define PWDN_GPIO_NUM -1
#define RESET_GPIO_NUM -1
#define XCLK_GPIO_NUM 10
#define SIOD_GPIO_NUM 40
#define SIOC_GPIO_NUM 39
#define Y9_GPIO_NUM 48
#define Y8_GPIO_NUM 11
#define Y7_GPIO_NUM 12
#define Y6_GPIO_NUM 14
#define Y5_GPIO_NUM 16
#define Y4_GPIO_NUM 18
#define Y3_GPIO_NUM 17
#define Y2_GPIO_NUM 15
#define VSYNC_GPIO_NUM 38
#define HREF_GPIO_NUM 47
#define PCLK_GPIO_NUM 13
#define LED_GPIO_NUM 21
#else
#error "Camera model not selected"
#endif
// web page for remote control and screen * * * * * * * * * * * * *
static const char* _STREAM_CONTENT_TYPE = "multipart/x-mixed-replace;boundary=" PART_BOUNDARY;
static const char* _STREAM_BOUNDARY = "\r\n--" PART_BOUNDARY "\r\n";
static const char* _STREAM_PART = "Content-Type: image/jpeg\r\nContent-Length: %u\r\n\r\n";
httpd_handle_t camera_httpd = NULL;
httpd_handle_t stream_httpd = NULL;
static const char PROGMEM INDEX_HTML[] = R"rawliteral(
<html>
<head>
<title>Red Ant</title>
<meta name="viewport" content="width=device-width, initial-scale=1">
<style>
body { font-family: Arial; text-align: center; margin:0px auto; padding-top: 30px; background-color: #010101; color: orange;}
table { margin-left: auto; margin-right: auto; }
td { padding: 8 px; }
.button1 {
background-color: #f93e16;
border: 1;
color: white;
padding: 10px 20px;
text-align: center;
text-decoration: none;
display: inline-block;
font-size: 32px;
margin: 6px 3px;
cursor: pointer;
-webkit-touch-callout: none;
-webkit-user-select: none;
-khtml-user-select: none;
-moz-user-select: none;
-ms-user-select: none;
user-select: none;
-webkit-tap-highlight-color: rgba(0,0,0,0);
}
.button2 {
background-color: #4EB232;
border: 1;
color: white;
padding: 10px 20px;
text-align: center;
text-decoration: none;
display: inline-block;
font-size: 18px;
margin: 6px 3px;
cursor: pointer;
-webkit-touch-callout: none;
-webkit-user-select: none;
-khtml-user-select: none;
-moz-user-select: none;
-ms-user-select: none;
user-select: none;
-webkit-tap-highlight-color: rgba(0,0,0,0);
}
img { width: auto ;
max-width: 100% ;
height: auto ;
}
</style>
</head>
<body>
<h1>Red Ant</h1>
<img src="" id="photo">
<table>
<tr>
<td align="center"><button1 class="button1" onmousedown="toggleCheckbox('left');" ontouchstart="toggleCheckbox('left');" onmouseup="toggleCheckbox('stop');" ontouchend="toggleCheckbox('stop');">↖</button1></td>
<td align="center"><button1 class="button1" onmousedown="toggleCheckbox('forward');" ontouchstart="toggleCheckbox('forward');" onmouseup="toggleCheckbox('stop');" ontouchend="toggleCheckbox('stop');"> ↑ ↑ </button1></td>
<td align="center"><button1 class="button1" onmousedown="toggleCheckbox('right');" ontouchstart="toggleCheckbox('right');" onmouseup="toggleCheckbox('stop');" ontouchend="toggleCheckbox('stop');">↗</button1></td>
</tr>
<tr><td align="center"><button1 class="button1" onmousedown="toggleCheckbox('turnleft');" ontouchstart="toggleCheckbox('turnleft');" onmouseup="toggleCheckbox('stop');" ontouchend="toggleCheckbox('stop');">↶</button1></td>
<td align="center"><button1 class="button1" onmousedown="toggleCheckbox('rise');" ontouchstart="toggleCheckbox('rise');" onmouseup="toggleCheckbox('stop');" ontouchend="toggleCheckbox('stop');">⟰</button1></td>/
<td align="center"><button1 class="button1" onmousedown="toggleCheckbox('turnright');" ontouchstart="toggleCheckbox('turnright');" onmouseup="toggleCheckbox('stop');" ontouchend="toggleCheckbox('stop');">↷</button1></td></tr>
<tr><td colspan="3" align="center"><button1 class="button1" onmousedown="toggleCheckbox('backward');" ontouchstart="toggleCheckbox('backward');" onmouseup="toggleCheckbox('stop');" ontouchend="toggleCheckbox('stop');">↓</button1></td></tr>
<tr><td colspan="3" align="center"><button2 class="button2" onmousedown="toggleCheckbox('automode');" ontouchstart="toggleCheckbox('automode');" onmouseup="toggleCheckbox('stop');" ontouchend="toggleCheckbox('stop');">Auto Mode</button1></td></tr>
</table>
<script>
function toggleCheckbox(x) {
var xhr = new XMLHttpRequest();
xhr.open("GET", "/action?go=" + x, true);
xhr.send();
}
window.onload = document.getElementById("photo").src = window.location.href.slice(0, -1) + ":81/stream";
</script>
</body>
</html>
)rawliteral";
static esp_err_t index_handler(httpd_req_t *req){
httpd_resp_set_type(req, "text/html");
return httpd_resp_send(req, (const char *)INDEX_HTML, strlen(INDEX_HTML));
}
static esp_err_t stream_handler(httpd_req_t *req){
camera_fb_t * fb = NULL;
esp_err_t res = ESP_OK;
size_t _jpg_buf_len = 0;
uint8_t * _jpg_buf = NULL;
char * part_buf[64];
res = httpd_resp_set_type(req, _STREAM_CONTENT_TYPE);
if(res != ESP_OK){
return res;
}
while(true){
fb = esp_camera_fb_get();
if (!fb) {
Serial.println("Camera capture failed");
res = ESP_FAIL;
} else {
if(fb->width > 400){
if(fb->format != PIXFORMAT_JPEG){
bool jpeg_converted = frame2jpg(fb, 80, &_jpg_buf, &_jpg_buf_len);
esp_camera_fb_return(fb);
fb = NULL;
if(!jpeg_converted){
Serial.println("JPEG compression failed");
res = ESP_FAIL;
}
} else {
_jpg_buf_len = fb->len;
_jpg_buf = fb->buf;
}
}
}
if(res == ESP_OK){
size_t hlen = snprintf((char *)part_buf, 64, _STREAM_PART, _jpg_buf_len);
res = httpd_resp_send_chunk(req, (const char *)part_buf, hlen);
}
if(res == ESP_OK){
res = httpd_resp_send_chunk(req, (const char *)_jpg_buf, _jpg_buf_len);
}
if(res == ESP_OK){
res = httpd_resp_send_chunk(req, _STREAM_BOUNDARY, strlen(_STREAM_BOUNDARY));
}
if(fb){
esp_camera_fb_return(fb);
fb = NULL;
_jpg_buf = NULL;
} else if(_jpg_buf){
free(_jpg_buf);
_jpg_buf = NULL;
}
if(res != ESP_OK){
break;
}
//Serial.printf("MJPG: %uB\n",(uint32_t)(_jpg_buf_len));
}
return res;
}
static esp_err_t cmd_handler(httpd_req_t *req){
char* buf;
size_t buf_len;
char variable[32] = {0,};
buf_len = httpd_req_get_url_query_len(req) + 1;
if (buf_len > 1) {
buf = (char*)malloc(buf_len);
if(!buf){
httpd_resp_send_500(req);
return ESP_FAIL;
}
if (httpd_req_get_url_query_str(req, buf, buf_len) == ESP_OK) {
if (httpd_query_key_value(buf, "go", variable, sizeof(variable)) == ESP_OK) {
} else {
free(buf);
httpd_resp_send_404(req);
return ESP_FAIL;
}
} else {
free(buf);
httpd_resp_send_404(req);
return ESP_FAIL;
}
free(buf);
} else {
httpd_resp_send_404(req);
return ESP_FAIL;
}
sensor_t * s = esp_camera_sensor_get();
int res = 0;
if(!strcmp(variable, "forward")) {
Serial.println("Forward");
forward();
}
else if(!strcmp(variable, "left")) {
Serial.println("Left");
left();
}
else if(!strcmp(variable, "right")) {
Serial.println("Right");
right();
}
else if(!strcmp(variable, "backward")) {
Serial.println("Backward");
backward();
}
else if(!strcmp(variable, "turnleft")) {
Serial.println("turn left");
}
else if(!strcmp(variable, "turnright")) {
Serial.println("turn right");
}
else if(!strcmp(variable, "rise")) {
Serial.println("rise");
rise();
}
else if(!strcmp(variable, "stop")) {
Serial.println("stop");
stop();
}
else if(!strcmp(variable, "automode")) {
Serial.println("auto modus");
if (flag = 0) flag =1;
if (flag = 1) flag =0;
//automode
}
else { //stop
servo1.write(center1); //al servos in start position
servo2.write(center2);
servo3.write(center3);
servo4.write(center4);
servo5.write(center5);
servo6.write(center6);
delay(2000);
//res = -1;
}
if (flag =1){
automode();
}
if(res){
return httpd_resp_send_500(req);
}
httpd_resp_set_hdr(req, "Access-Control-Allow-Origin", "*");
return httpd_resp_send(req, NULL, 0);
}
void startCameraServer(){
httpd_config_t config = HTTPD_DEFAULT_CONFIG();
config.server_port = 80;
httpd_uri_t index_uri = {
.uri = "/",
.method = HTTP_GET,
.handler = index_handler,
.user_ctx = NULL
};
httpd_uri_t cmd_uri = {
.uri = "/action",
.method = HTTP_GET,
.handler = cmd_handler,
.user_ctx = NULL
};
httpd_uri_t stream_uri = {
.uri = "/stream",
.method = HTTP_GET,
.handler = stream_handler,
.user_ctx = NULL
};
if (httpd_start(&camera_httpd, &config) == ESP_OK) {
httpd_register_uri_handler(camera_httpd, &index_uri);
httpd_register_uri_handler(camera_httpd, &cmd_uri);
}
config.server_port += 1;
config.ctrl_port += 1;
if (httpd_start(&stream_httpd, &config) == ESP_OK) {
httpd_register_uri_handler(stream_httpd, &stream_uri);
}
}
void setup() {
WRITE_PERI_REG(RTC_CNTL_BROWN_OUT_REG, 0); //disable brownout detector
Serial.begin(115200);
Serial.setDebugOutput(false);
// button * * * * * * * * * * * * * * * * * *
pinMode(buttonLeft, INPUT_PULLUP);
pinMode(buttonRight, INPUT_PULLUP);
// servos * * * * * * * * * * * * * * * * * *
servo1.attach(6); //please check the correct wiring
servo2.attach(5);
servo3.attach(44);
servo4.attach(7);
servo5.attach(8);
servo6.attach(9);
delay(20);
servo1.write(center1); //all servos in start position
servo2.write(center2);
servo3.write(center3);
servo4.write(center4);
servo5.write(center5);
servo6.write(center6);
delay(2000); //wait
// camera * * * * * * * * * * * * * * * * * *
camera_config_t config;
config.ledc_channel = LEDC_CHANNEL_0;
config.ledc_timer = LEDC_TIMER_0;
config.pin_d0 = Y2_GPIO_NUM;
config.pin_d1 = Y3_GPIO_NUM;
config.pin_d2 = Y4_GPIO_NUM;
config.pin_d3 = Y5_GPIO_NUM;
config.pin_d4 = Y6_GPIO_NUM;
config.pin_d5 = Y7_GPIO_NUM;
config.pin_d6 = Y8_GPIO_NUM;
config.pin_d7 = Y9_GPIO_NUM;
config.pin_xclk = XCLK_GPIO_NUM;
config.pin_pclk = PCLK_GPIO_NUM;
config.pin_vsync = VSYNC_GPIO_NUM;
config.pin_href = HREF_GPIO_NUM;
config.pin_sscb_sda = SIOD_GPIO_NUM;
config.pin_sscb_scl = SIOC_GPIO_NUM;
config.pin_pwdn = PWDN_GPIO_NUM;
config.pin_reset = RESET_GPIO_NUM;
config.xclk_freq_hz = 20000000;
config.frame_size = FRAMESIZE_VGA; //choose the prefered size
/*UXGA(1600x1200)
SXGA(1280x1024)
XGA(1024x768)
SVGA(800x600)
VGA(640x480)
CIF(400x296)
QVGA(320x240)
HQVGA(240x176)
QQVGA(160x120)
*/
config.pixel_format = PIXFORMAT_JPEG; // for streaming
config.grab_mode = CAMERA_GRAB_WHEN_EMPTY;
config.fb_location = CAMERA_FB_IN_PSRAM;
//config.jpeg_quality = 12; //10-63 lower number means higher quality
config.jpeg_quality = 18;
config.fb_count = 1;
// if PSRAM IC present, init with UXGA resolution and higher JPEG quality
// for larger pre-allocated frame buffer.
if(config.pixel_format == PIXFORMAT_JPEG){
if(psramFound()){
config.jpeg_quality = 10;
config.fb_count = 2;
config.grab_mode = CAMERA_GRAB_LATEST;
} else {
// Limit the frame size when PSRAM is not available
config.frame_size = FRAMESIZE_CIF;
config.fb_location = CAMERA_FB_IN_DRAM;
}
} else {
// Best option for face detection/recognition
config.frame_size = FRAMESIZE_240X240;
#if CONFIG_IDF_TARGET_ESP32S3
config.fb_count = 2;
#endif
}
// Camera init
esp_err_t err = esp_camera_init(&config);
if (err != ESP_OK) {
Serial.printf("Camera init failed with error 0x%x", err);
return;
}
// Wi-Fi connection
WiFi.begin(ssid, password);
while (WiFi.status() != WL_CONNECTED) {
delay(500);
Serial.print(".");
}
Serial.println("");
Serial.println("WiFi connected");
Serial.print("Camera Stream Ready! Go to: http://");
Serial.println(WiFi.localIP());
// Start streaming web server
startCameraServer();
}
void loop() {
}
// walking modes * * * * * * * * * * * * * * * * * *
void forward() {
servo3.write(center3 - 10); //left mid down
servo4.write(center4 - 10); //right mid up
delay(20);
servo1.write(center1 - steplength); //left side forward
delay(30);
servo5.write(center5 - steplength);
servo2.write(center2 - steplength); //right side backwards/give push
delay(30);
servo6.write(center6 - steplength);
delay(speed1);
servo3.write(center3 + 10); //left mid up
servo4.write(center4 + 10); //right mid down
delay(20);
servo1.write(center1 + steplength); //left side backwards/give push
delay(30);
servo5.write(center5 + steplength);
servo2.write(center2 + steplength); //right side forward
delay(30);
servo6.write(center6 + steplength);
delay(speed1);
}
void left() {
servo3.write(center3 - 10); //left mid down
servo4.write(center4 - 10); //right mid up
delay(20);
servo1.write(center1 - smallstep); //left side forward
servo5.write(center5 - smallstep);
servo2.write(center2 - steplength); //right side backwards/give push
servo6.write(center6 - steplength);
delay(speed1);
servo3.write(center3 + 10); //left mid up
servo4.write(center4 + 10); //right mid down
delay(20);
servo1.write(center1 + smallstep); //left side backwards/give push
servo5.write(center5 + smallstep);
servo2.write(center2 + steplength); //right side forward
servo6.write(center6 + steplength);
delay(speed1);
}
void right() {
servo3.write(center3 + 10); //left mid up
servo4.write(center4 + 10); //right mid down
delay(20);
servo1.write(center1 + steplength); //left side backward/give push
servo5.write(center5 + steplength);
servo2.write(center2 + smallstep); //right side forward
servo6.write(center6 + smallstep);
delay(speed1);
servo3.write(center3 - 10); //left mid down
servo4.write(center4 - 10); //right mid up
delay(20);
servo1.write(center1 - steplength); //left side forward
servo5.write(center5 - steplength);
servo2.write(center2 - smallstep); //right side backwards/give push
servo6.write(center6 - smallstep);
delay(speed1);
}
void backward() {
servo3.write(center3 + 10); //left mid up
servo4.write(center4 + 10); //right mid down
delay(20);
servo1.write(center1 - steplength); //left side forward/give push
delay(30);
servo5.write(center5 - steplength);
servo2.write(center2 - steplength); //right side backwards
delay(30);
servo6.write(center6 - steplength);
delay(speed1 + 100);
servo3.write(center3 - 10); //left mid down
servo4.write(center4 - 10); //right mid up
delay(20);
servo1.write(center1 + steplength); //left side backwards
delay(30);
servo5.write(center5 + steplength);
servo2.write(center2 + steplength); //right side forward/give push
delay(30);
servo6.write(center6 + steplength);
delay(speed1 + 100);
}
void rise() {
servo1.write(center1 - 30); //front legs up
servo2.write(center2 + 30);
servo3.write(center3 - 20); //left mid down
servo4.write(center4 + 20); //right mid down
servo5.write(center5 - 25); //rear legs centered
servo6.write(center6 + 25);
delay(100);
}
void stop() {
servo1.write(center1);
servo2.write(center2);
servo3.write(center3);
servo4.write(center4);
servo5.write(center5);
servo6.write(center6);
delay(50);
}
void automode(){
leftState = digitalRead(buttonLeft);
rightState = digitalRead(buttonRight);
delay(50);
if ((leftState == LOW) && (leftState == HIGH)) {
Serial.println("stop and go right");
for (int i = 0; i<=3; i++){
backward();
}
for (int i = 0; i<=3; i++){
right();
}
}
if ((leftState == HIGH) && (leftState == LOW)) {
Serial.println("stop and go left");
for (int i = 0; i<=3; i++){
backward();
}
for (int i = 0; i<=3; i++){
left();
}
}
if ((leftState == LOW) && (leftState == LOW)) {
Serial.println("stop, go back and try again");
for (int i = 0; i<=6; i++){
backward();
}
for (int i = 0; i<=5; i++){
left();
}
}
else {
forward();
}
if (flag = 0) {
return;
}
delay(200);
}
Remote Control and Video Stream
The Ant can be integrated into your wifi network or serve as an access point (AP) itself. The AP mode is described here:
Activate the red ant with the switch. After a few seconds, you can scan for a new Wi-Fi network with your PC or smartphone. Dial into the "Red_Ant_Access" network (no password required). Open the address "192.168.4.1" in your browser and you have a remote control with an ant screen.
You now have the choice between forwards, backwards, left, right, turn and straighten up as long as you keep your finger on a button.
/*
* ESP32S3 XIAO Red Ant Remote Control - Access Point
* make sure that PSRAM is enabled
*/
// servos * * * * * * * * * * * * * * * * * * * *
#include <s3servo.h>
s3servo servo1;
s3servo servo2;
s3servo servo3;
s3servo servo4;
s3servo servo5;
s3servo servo6;
int center1 = 75; //best center position of each leg (individual)
int center2 = 105;
int center3 = 90;
int center4 = 90;
int center5 = 115;
int center6 = 75;
int pos = 90;
int pos2;
int Min = 50; //move betwenn this two values
int Max = 100;
int speed1 = 350; //pause between forward and backward movement
int steplength = 30; //big step
int smallstep = 5; //small step
int flag = 0;
// button * * * * * * * * * * * * * * * * * * * *
const int buttonLeft = 5;
const int buttonRight = 6;
int leftState =0;
int rightState =0;
// camera * * * * * * * * * * * * * * * * * * * *
#include "esp_camera.h"
#include <WiFi.h>
#include "esp_timer.h"
#include "img_converters.h"
#include "Arduino.h"
#include "fb_gfx.h"
#include "soc/soc.h" // disable brownout problems
#include "soc/rtc_cntl_reg.h" // disable brownout problems
#include "esp_http_server.h"
#include "esp_http_server.h"
#include "esp32-hal-ledc.h"
#include "sdkconfig.h"
#define CAMERA_MODEL_XIAO_ESP32S3 // Has PSRAM
#if defined(ARDUINO_ARCH_ESP32) && defined(CONFIG_ARDUHAL_ESP_LOG)
#include "esp32-hal-log.h"
#endif
// Replace with your network data
const char* ssid = "Red_Ant_Access"; //or set another name
//const char* password = "xxx"; //set you own password
#define PART_BOUNDARY "123456789000000000000987654321"
#define CAMERA_MODEL_AI_THINKER
//#define CAMERA_MODEL_WROVER_KIT
#if defined(CAMERA_MODEL_XIAO_ESP32S3)
#define PWDN_GPIO_NUM -1
#define RESET_GPIO_NUM -1
#define XCLK_GPIO_NUM 10
#define SIOD_GPIO_NUM 40
#define SIOC_GPIO_NUM 39
#define Y9_GPIO_NUM 48
#define Y8_GPIO_NUM 11
#define Y7_GPIO_NUM 12
#define Y6_GPIO_NUM 14
#define Y5_GPIO_NUM 16
#define Y4_GPIO_NUM 18
#define Y3_GPIO_NUM 17
#define Y2_GPIO_NUM 15
#define VSYNC_GPIO_NUM 38
#define HREF_GPIO_NUM 47
#define PCLK_GPIO_NUM 13
#define LED_GPIO_NUM 21
#else
#error "Camera model not selected"
#endif
// web page for remote control and screen * * * * * * * * * * * * *
static const char* _STREAM_CONTENT_TYPE = "multipart/x-mixed-replace;boundary=" PART_BOUNDARY;
static const char* _STREAM_BOUNDARY = "\r\n--" PART_BOUNDARY "\r\n";
static const char* _STREAM_PART = "Content-Type: image/jpeg\r\nContent-Length: %u\r\n\r\n";
httpd_handle_t camera_httpd = NULL;
httpd_handle_t stream_httpd = NULL;
static const char PROGMEM INDEX_HTML[] = R"rawliteral(
<html>
<head>
<title>Red Ant</title>
<meta name="viewport" content="width=device-width, initial-scale=1">
<style>
body { font-family: Arial; text-align: center; margin:0px auto; padding-top: 30px; background-color: #010101; color: orange;}
table { margin-left: auto; margin-right: auto; }
td { padding: 8 px; }
.button1 {
background-color: #f93e16;
border: 1;
color: white;
padding: 10px 20px;
text-align: center;
text-decoration: none;
display: inline-block;
font-size: 32px;
margin: 6px 3px;
cursor: pointer;
-webkit-touch-callout: none;
-webkit-user-select: none;
-khtml-user-select: none;
-moz-user-select: none;
-ms-user-select: none;
user-select: none;
-webkit-tap-highlight-color: rgba(0,0,0,0);
}
.button2 {
background-color: #4EB232;
border: 1;
color: white;
padding: 10px 20px;
text-align: center;
text-decoration: none;
display: inline-block;
font-size: 18px;
margin: 6px 3px;
cursor: pointer;
-webkit-touch-callout: none;
-webkit-user-select: none;
-khtml-user-select: none;
-moz-user-select: none;
-ms-user-select: none;
user-select: none;
-webkit-tap-highlight-color: rgba(0,0,0,0);
}
img { width: auto ;
max-width: 100% ;
height: auto ;
}
</style>
</head>
<body>
<h1>Red Ant</h1>
<img src="" id="photo">
<table>
<tr>
<td align="center"><button1 class="button1" onmousedown="toggleCheckbox('left');" ontouchstart="toggleCheckbox('left');" onmouseup="toggleCheckbox('stop');" ontouchend="toggleCheckbox('stop');">↖</button1></td>
<td align="center"><button1 class="button1" onmousedown="toggleCheckbox('forward');" ontouchstart="toggleCheckbox('forward');" onmouseup="toggleCheckbox('stop');" ontouchend="toggleCheckbox('stop');"> ↑ ↑ </button1></td>
<td align="center"><button1 class="button1" onmousedown="toggleCheckbox('right');" ontouchstart="toggleCheckbox('right');" onmouseup="toggleCheckbox('stop');" ontouchend="toggleCheckbox('stop');">↗</button1></td>
</tr>
<tr><td align="center"><button1 class="button1" onmousedown="toggleCheckbox('turnleft');" ontouchstart="toggleCheckbox('turnleft');" onmouseup="toggleCheckbox('stop');" ontouchend="toggleCheckbox('stop');">↶</button1></td>
<td align="center"><button1 class="button1" onmousedown="toggleCheckbox('rise');" ontouchstart="toggleCheckbox('rise');" onmouseup="toggleCheckbox('stop');" ontouchend="toggleCheckbox('stop');">⟰</button1></td>/
<td align="center"><button1 class="button1" onmousedown="toggleCheckbox('turnright');" ontouchstart="toggleCheckbox('turnright');" onmouseup="toggleCheckbox('stop');" ontouchend="toggleCheckbox('stop');">↷</button1></td></tr>
<tr><td colspan="3" align="center"><button1 class="button1" onmousedown="toggleCheckbox('backward');" ontouchstart="toggleCheckbox('backward');" onmouseup="toggleCheckbox('stop');" ontouchend="toggleCheckbox('stop');">↓</button1></td></tr>
<tr><td colspan="3" align="center"><button2 class="button2" onmousedown="toggleCheckbox('automode');" ontouchstart="toggleCheckbox('automode');" onmouseup="toggleCheckbox('stop');" ontouchend="toggleCheckbox('stop');">Auto Mode</button1></td></tr>
</table>
<script>
function toggleCheckbox(x) {
var xhr = new XMLHttpRequest();
xhr.open("GET", "/action?go=" + x, true);
xhr.send();
}
window.onload = document.getElementById("photo").src = window.location.href.slice(0, -1) + ":81/stream";
</script>
</body>
</html>
)rawliteral";
static esp_err_t index_handler(httpd_req_t *req){
httpd_resp_set_type(req, "text/html");
return httpd_resp_send(req, (const char *)INDEX_HTML, strlen(INDEX_HTML));
}
static esp_err_t stream_handler(httpd_req_t *req){
camera_fb_t * fb = NULL;
esp_err_t res = ESP_OK;
size_t _jpg_buf_len = 0;
uint8_t * _jpg_buf = NULL;
char * part_buf[64];
res = httpd_resp_set_type(req, _STREAM_CONTENT_TYPE);
if(res != ESP_OK){
return res;
}
while(true){
fb = esp_camera_fb_get();
if (!fb) {
Serial.println("Camera capture failed");
res = ESP_FAIL;
} else {
if(fb->width > 400){
if(fb->format != PIXFORMAT_JPEG){
bool jpeg_converted = frame2jpg(fb, 80, &_jpg_buf, &_jpg_buf_len);
esp_camera_fb_return(fb);
fb = NULL;
if(!jpeg_converted){
Serial.println("JPEG compression failed");
res = ESP_FAIL;
}
} else {
_jpg_buf_len = fb->len;
_jpg_buf = fb->buf;
}
}
}
if(res == ESP_OK){
size_t hlen = snprintf((char *)part_buf, 64, _STREAM_PART, _jpg_buf_len);
res = httpd_resp_send_chunk(req, (const char *)part_buf, hlen);
}
if(res == ESP_OK){
res = httpd_resp_send_chunk(req, (const char *)_jpg_buf, _jpg_buf_len);
}
if(res == ESP_OK){
res = httpd_resp_send_chunk(req, _STREAM_BOUNDARY, strlen(_STREAM_BOUNDARY));
}
if(fb){
esp_camera_fb_return(fb);
fb = NULL;
_jpg_buf = NULL;
} else if(_jpg_buf){
free(_jpg_buf);
_jpg_buf = NULL;
}
if(res != ESP_OK){
break;
}
//Serial.printf("MJPG: %uB\n",(uint32_t)(_jpg_buf_len));
}
return res;
}
static esp_err_t cmd_handler(httpd_req_t *req){
char* buf;
size_t buf_len;
char variable[32] = {0,};
buf_len = httpd_req_get_url_query_len(req) + 1;
if (buf_len > 1) {
buf = (char*)malloc(buf_len);
if(!buf){
httpd_resp_send_500(req);
return ESP_FAIL;
}
if (httpd_req_get_url_query_str(req, buf, buf_len) == ESP_OK) {
if (httpd_query_key_value(buf, "go", variable, sizeof(variable)) == ESP_OK) {
} else {
free(buf);
httpd_resp_send_404(req);
return ESP_FAIL;
}
} else {
free(buf);
httpd_resp_send_404(req);
return ESP_FAIL;
}
free(buf);
} else {
httpd_resp_send_404(req);
return ESP_FAIL;
}
sensor_t * s = esp_camera_sensor_get();
int res = 0;
if(!strcmp(variable, "forward")) {
Serial.println("Forward");
forward();
}
else if(!strcmp(variable, "left")) {
Serial.println("Left");
left();
}
else if(!strcmp(variable, "right")) {
Serial.println("Right");
right();
}
else if(!strcmp(variable, "backward")) {
Serial.println("Backward");
backward();
}
else if(!strcmp(variable, "turnleft")) {
Serial.println("turn left");
}
else if(!strcmp(variable, "turnright")) {
Serial.println("turn right");
}
else if(!strcmp(variable, "rise")) {
Serial.println("rise");
rise();
}
else if(!strcmp(variable, "automode")) {
Serial.println("auto modus");
if (flag = 0) flag =1;
if (flag = 1) flag =0;
//automode
}
else { //stop
servo1.write(center1); //al servos in start position
servo2.write(center2);
servo3.write(center3);
servo4.write(center4);
servo5.write(center5);
servo6.write(center6);
delay(2000);
//res = -1;
}
if (flag =1){
automode();
}
if(res){
return httpd_resp_send_500(req);
}
httpd_resp_set_hdr(req, "Access-Control-Allow-Origin", "*");
return httpd_resp_send(req, NULL, 0);
}
void startCameraServer(){
httpd_config_t config = HTTPD_DEFAULT_CONFIG();
config.server_port = 80;
httpd_uri_t index_uri = {
.uri = "/",
.method = HTTP_GET,
.handler = index_handler,
.user_ctx = NULL
};
httpd_uri_t cmd_uri = {
.uri = "/action",
.method = HTTP_GET,
.handler = cmd_handler,
.user_ctx = NULL
};
httpd_uri_t stream_uri = {
.uri = "/stream",
.method = HTTP_GET,
.handler = stream_handler,
.user_ctx = NULL
};
if (httpd_start(&camera_httpd, &config) == ESP_OK) {
httpd_register_uri_handler(camera_httpd, &index_uri);
httpd_register_uri_handler(camera_httpd, &cmd_uri);
}
config.server_port += 1;
config.ctrl_port += 1;
if (httpd_start(&stream_httpd, &config) == ESP_OK) {
httpd_register_uri_handler(stream_httpd, &stream_uri);
}
}
void setup() {
WRITE_PERI_REG(RTC_CNTL_BROWN_OUT_REG, 0); //disable brownout detector
Serial.begin(115200);
Serial.setDebugOutput(false);
// button * * * * * * * * * * * * * * * * * *
pinMode(buttonLeft, INPUT_PULLUP);
pinMode(buttonRight, INPUT_PULLUP);
// servos * * * * * * * * * * * * * * * * * *
servo1.attach(6);
servo2.attach(5);
servo3.attach(44);
servo4.attach(7);
servo5.attach(8);
servo6.attach(9);
delay(20);
servo1.write(center1); //al servos in start position
servo2.write(center2);
servo3.write(center3);
servo4.write(center4);
servo5.write(center5);
servo6.write(center6);
delay(2000); //wait
// camera * * * * * * * * * * * * * * * * * *
camera_config_t config;
config.ledc_channel = LEDC_CHANNEL_0;
config.ledc_timer = LEDC_TIMER_0;
config.pin_d0 = Y2_GPIO_NUM;
config.pin_d1 = Y3_GPIO_NUM;
config.pin_d2 = Y4_GPIO_NUM;
config.pin_d3 = Y5_GPIO_NUM;
config.pin_d4 = Y6_GPIO_NUM;
config.pin_d5 = Y7_GPIO_NUM;
config.pin_d6 = Y8_GPIO_NUM;
config.pin_d7 = Y9_GPIO_NUM;
config.pin_xclk = XCLK_GPIO_NUM;
config.pin_pclk = PCLK_GPIO_NUM;
config.pin_vsync = VSYNC_GPIO_NUM;
config.pin_href = HREF_GPIO_NUM;
config.pin_sscb_sda = SIOD_GPIO_NUM;
config.pin_sscb_scl = SIOC_GPIO_NUM;
config.pin_pwdn = PWDN_GPIO_NUM;
config.pin_reset = RESET_GPIO_NUM;
config.xclk_freq_hz = 20000000;
config.frame_size = FRAMESIZE_VGA; //choose the prefered size
/*UXGA(1600x1200)
SXGA(1280x1024)
XGA(1024x768)
SVGA(800x600)
VGA(640x480)
CIF(400x296)
QVGA(320x240)
HQVGA(240x176)
QQVGA(160x120)
*/
config.pixel_format = PIXFORMAT_JPEG; // for streaming
config.grab_mode = CAMERA_GRAB_WHEN_EMPTY;
config.fb_location = CAMERA_FB_IN_PSRAM;
config.jpeg_quality = 12;
config.fb_count = 1;
// if PSRAM IC present, init with UXGA resolution and higher JPEG quality
// for larger pre-allocated frame buffer.
if(config.pixel_format == PIXFORMAT_JPEG){
if(psramFound()){
config.jpeg_quality = 10;
config.fb_count = 2;
config.grab_mode = CAMERA_GRAB_LATEST;
} else {
// Limit the frame size when PSRAM is not available
config.frame_size = FRAMESIZE_CIF;
config.fb_location = CAMERA_FB_IN_DRAM;
}
} else {
// Best option for face detection/recognition
config.frame_size = FRAMESIZE_240X240;
#if CONFIG_IDF_TARGET_ESP32S3
config.fb_count = 2;
#endif
}
// Camera init
esp_err_t err = esp_camera_init(&config);
if (err != ESP_OK) {
Serial.printf("Camera init failed with error 0x%x", err);
return;
}
// Wi-Fi connection (Soft Access Point)
WiFi.softAP(ssid);
/*
// Wi-Fi connection for your network
WiFi.begin(ssid, password);
while (WiFi.status() != WL_CONNECTED) {
delay(500);
Serial.print(".");
}
*/
Serial.println("");
Serial.println("WiFi connected");
Serial.print("Camera Stream Ready! Go to: http://");
Serial.println(WiFi.localIP());
// Start streaming web server
startCameraServer();
}
void loop() {
}
// walking modes * * * * * * * * * * * * * * * * * *
void forward() {
servo3.write(center3 - 10); //left mid down
servo4.write(center4 - 10); //right mid up
delay(20);
servo1.write(center1 - steplength); //left side forward
delay(30);
servo5.write(center5 - steplength);
servo2.write(center2 - steplength); //right side backwards/give push
delay(30);
servo6.write(center6 - steplength);
delay(speed1);
servo3.write(center3 + 10); //left mid up
servo4.write(center4 + 10); //right mid down
delay(20);
servo1.write(center1 + steplength); //left side backwards/give push
delay(30);
servo5.write(center5 + steplength);
servo2.write(center2 + steplength); //right side forward
delay(30);
servo6.write(center6 + steplength);
delay(speed1);
}
void left() {
servo3.write(center3 - 10); //left mid down
servo4.write(center4 - 10); //right mid up
delay(20);
servo1.write(center1 - smallstep); //left side forward
servo5.write(center5 - smallstep);
servo2.write(center2 - steplength); //right side backwards/give push
servo6.write(center6 - steplength);
delay(speed1);
servo3.write(center3 + 10); //left mid up
servo4.write(center4 + 10); //right mid down
delay(20);
servo1.write(center1 + smallstep); //left side backwards/give push
servo5.write(center5 + smallstep);
servo2.write(center2 + steplength); //right side forward
servo6.write(center6 + steplength);
delay(speed1);
}
void right() {
servo3.write(center3 + 10); //left mid up
servo4.write(center4 + 10); //right mid down
delay(20);
servo1.write(center1 + steplength); //left side backward/give push
servo5.write(center5 + steplength);
servo2.write(center2 + smallstep); //right side forward
servo6.write(center6 + smallstep);
delay(speed1);
servo3.write(center3 - 10); //left mid down
servo4.write(center4 - 10); //right mid up
delay(20);
servo1.write(center1 - steplength); //left side forward
servo5.write(center5 - steplength);
servo2.write(center2 - smallstep); //right side backwards/give push
servo6.write(center6 - smallstep);
delay(speed1);
}
void backward() {
servo3.write(center3 + 10); //left mid up
servo4.write(center4 + 10); //right mid down
delay(20);
servo1.write(center1 - steplength); //left side forward/give push
delay(30);
servo5.write(center5 - steplength);
servo2.write(center2 - steplength); //right side backwards
delay(30);
servo6.write(center6 - steplength);
delay(speed1 + 100);
servo3.write(center3 - 10); //left mid down
servo4.write(center4 - 10); //right mid up
delay(20);
servo1.write(center1 + steplength); //left side backwards
delay(30);
servo5.write(center5 + steplength);
servo2.write(center2 + steplength); //right side forward/give push
delay(30);
servo6.write(center6 + steplength);
delay(speed1 + 100);
}
void rise() {
servo1.write(center1 - 30); //front legs up
servo2.write(center2 + 30);
servo3.write(center3 - 20); //left mid down
servo4.write(center4 + 20); //right mid down
servo5.write(center5 - 25); //rear legs centered
servo6.write(center6 + 25);
delay(100);
}
void automode(){
leftState = digitalRead(buttonLeft);
rightState = digitalRead(buttonRight);
delay(50);
if ((leftState == LOW) && (leftState == HIGH)) {
Serial.println("stop and go right");
for (int i = 0; i<=3; i++){
backward();
}
for (int i = 0; i<=3; i++){
right();
}
}
if ((leftState == HIGH) && (leftState == LOW)) {
Serial.println("stop and go left");
for (int i = 0; i<=3; i++){
backward();
}
for (int i = 0; i<=3; i++){
left();
}
}
if ((leftState == LOW) && (leftState == LOW)) {
Serial.println("stop, go back and try again");
for (int i = 0; i<=6; i++){
backward();
}
for (int i = 0; i<=5; i++){
left();
}
}
else {
forward();
}
if (flag = 0) {
return;
}
delay(200);
}
Autonomous Mode (with Head Sensors)
You can also let the red ant run independently by clicking on the green Auto Mode button. It will then navigate itself using its head sensors to decide whether to avoid an obstacle to the left or right.