仿生毛毛虫机器人Arduino源码
操作端是blinker
esp32通信
前后两个电机,一个舵机
主要涉及到电机调速, 舵机控制角度
没有多线程, 主要依靠中断处理程序
以下代码仅供参考
#include <ServoESP32.h>
#define BLINKER_WIFI
#include <Blinker.h>
#include <Arduino.h>
#define MOTOR1_STEPPIN 19
#define MOTOR1_DIRPIN 18
#define MOTOR2_STEPPIN 5
#define MOTOR2_DIRPIN 17
#define SERVO_PIN 16
#define MOTOR1_PWM 2
#define MOTOR2_PWM 0
char auth[] = "***";
char ssid[] = "***";
char pswd[] = "****";
int Speed1=0;
int Speed2=0;
int power=0;
int speed_direction=1;
int ANGLE = 90;
int UPPER_HIGH = 20;
// 新建组件对象
BlinkerButton Servo_state1("btn-servo1");
BlinkerButton Servo_state2("btn-servo2");
BlinkerButton Servo_state3("btn-servo3");
BlinkerButton switch_power("switch_power");
BlinkerButton speed_dir("speed_dir");
BlinkerSlider Slider_speed1("Slider_speed1");
BlinkerSlider Slider_speed2("Slider_speed2");
BlinkerSlider Slider_angle("Slider_angle");
Servo myservo;
bool setServoPos(char cmd){
int pos;
if(cmd == '0'){
pos=90-ANGLE;
}else if(cmd == '1'){
pos=90;
}else if(cmd == '2'){
pos=90+ANGLE;
}else{
return false;
}
myservo.write(pos);
delay(5);
return true;
}
// 按下按键即会执行该函数
void Servo_state1_callback(const String & state) {
BLINKER_LOG("get button state: ", state);
if (state=="tap"&&setServoPos('0')){
Servo_state1.print("Servo_state1 set success");
}else{
Servo_state1.print("Servo_state1 set failed");
}
}
void Servo_state2_callback(const String & state) {
BLINKER_LOG("get button state: ", state);
if (state=="tap"&&setServoPos('1')){
Servo_state2.print("Servo_state2 set success");
}else{
Servo_state2.print("Servo_state2 set failed");
}
}
void Servo_state3_callback(const String & state) {
BLINKER_LOG("get button state: ", state);
if (state=="tap"&&setServoPos('2')){
Servo_state3.print("Servo_state3 set success");
}else{
Servo_state3.print("Servo_state3 set failed");
}
}
void Speed1_set_callback(int s){
Speed1 = s;
Slider_speed1.print(s);
}
void Speed2_set_callback(int s){
Speed2 = s;
Slider_speed2.print(s);
}
void switch_power_callback(const String & state){
if(state=="tap"){
power=(power+1)%2;
if(power){
switch_power.print("power on");
if(speed_direction){
digitalWrite(MOTOR1_DIRPIN, HIGH);
digitalWrite(MOTOR1_STEPPIN, LOW);
digitalWrite(MOTOR2_DIRPIN, HIGH);
digitalWrite(MOTOR2_STEPPIN, LOW);
}else{
digitalWrite(MOTOR1_STEPPIN, HIGH);
digitalWrite(MOTOR1_DIRPIN, LOW);
digitalWrite(MOTOR2_STEPPIN, HIGH);
digitalWrite(MOTOR2_DIRPIN, LOW);
}
}else{
switch_power.print("power off");
digitalWrite(MOTOR1_DIRPIN, LOW);
digitalWrite(MOTOR1_STEPPIN, LOW);
digitalWrite(MOTOR2_DIRPIN, LOW);
digitalWrite(MOTOR2_STEPPIN, LOW);
}
}
}
void speed_dir_callback(const String & state){
if(state=="tap"){
speed_direction=(speed_direction+1)%2;
if(speed_direction){
speed_dir.print("direction 1");
}else{
speed_dir.print("direction 0");
}
}
if(speed_direction){
digitalWrite(MOTOR1_DIRPIN, HIGH);
digitalWrite(MOTOR1_STEPPIN, LOW);
digitalWrite(MOTOR2_DIRPIN, HIGH);
digitalWrite(MOTOR2_STEPPIN, LOW);
}else{
digitalWrite(MOTOR1_STEPPIN, HIGH);
digitalWrite(MOTOR1_DIRPIN, LOW);
digitalWrite(MOTOR2_STEPPIN, HIGH);
digitalWrite(MOTOR2_DIRPIN, LOW);
}
}
void Slider_angle_callback(int a){
ANGLE = a;
Slider_angle.print(a);
}
void setup() {
// 初始化串口
Serial.begin(115200);
// 初始化有LED的IO
pinMode(LED_BUILTIN, OUTPUT);
pinMode(MOTOR1_STEPPIN, OUTPUT);
pinMode(MOTOR2_STEPPIN, OUTPUT);
pinMode(MOTOR1_DIRPIN, OUTPUT);
pinMode(MOTOR2_DIRPIN, OUTPUT);
ledcAttachPin(MOTOR1_PWM, 3);
ledcAttachPin(MOTOR2_PWM, 2);
ledcSetup(3, 12000, 8);
ledcSetup(2, 12000, 8);
Blinker.begin(auth, ssid, pswd);
//舵机的三个状态
myservo.attach(SERVO_PIN);
Servo_state1.attach(Servo_state1_callback);
Servo_state2.attach(Servo_state2_callback);
Servo_state3.attach(Servo_state3_callback);
switch_power.attach(switch_power_callback);
speed_dir.attach(speed_dir_callback);
Slider_speed1.attach(Speed1_set_callback);
Slider_speed2.attach(Speed2_set_callback);
Slider_angle.attach(Slider_angle_callback);
}
void loop() {
Blinker.run();
for(int i=0;i<UPPER_HIGH;i++){
if(power){
ledcWrite(3,150+Speed1);
delay(20);
ledcWrite(2,150+Speed2);
}else{
ledcWrite(1,0);
ledcWrite(2,0);
}
}
}