/*******************************************************************************************************
实现功能:
用两个近红外传感器模拟小狗动作
实现思路:
如果左边的近红外传感器(A3)触发右边的近红外传感器(A4)没有触发,小狗右转;
如果左边的近红外传感器(A3)没有触发右边的近红外传感器(A4)触发,小狗左转;
如果左边的近红外传感器(A3)触发右边的近红外传感器(A4)触发,小狗后退;
否则,小狗前进;
实验接线:
小狗狗头侧左边的近红外传感器连接A3;
小狗狗头侧右边的近红外传感器连接A4;
头
外侧舵机:D3 外侧舵机:D8
内侧舵机:D4 内侧舵机:D7
._________________________
| |
| |
| |
| |
| |
| |
| |
| |
|_________________________|
外侧舵机:D11 外侧舵机:A16
内侧舵机:D12 内侧舵机:A14
尾
*******************************************************************************************************/
#include<Servo.h>
#define SERVO_SPEED 6 //定义舵机转动快慢的时间
#define SERVO_SPEED1 1
#define SERVO_SPEED_WalkForward_low 10 //设定小狗前进时的慢速的动作
#define SERVO_SPEED_WalkForward_high 3 //设定小狗前进时的快速的动作
#define SERVO_SPEED_WalkBack_low 10 //设定小狗后退时的慢速的动作
#define SERVO_SPEED_WalkBack_high 3 //设定小狗后退时的快速的动作
#define SERVO_SPEED_Right_low 4 //设定小狗右转时慢速动作时间
#define SERVO_SPEED_Right_high 1 //设定小狗右转快速动作时间
#define SERVO_SPEED_WALK 25
#define SERVO_SPEED_LEFT_HIGH 2 //设定小狗左转时快速动作时间
#define SERVO_SPEED_LEFT_LOW 5 //设定小狗左转时慢速动作时间
#define Servo_Speed_Walk 14
#define Servo_Speed_Quickly 1
#define ACTION_DELAY 0 //定义所有舵机每个状态时间间隔
Servo myServo[8];
int sensorpin[2]={A3,A4};
int sensornum=sizeof(sensorpin)/sizeof(sensorpin[0]);
int f = 20; //定义舵机每个状态间转动的次数,以此来确定每个舵机每次转动的角度
boolean BlueTooth = false;
int servo_port[8] = {3,4,7,8,11,12,16,14}; //定义舵机引脚
int servo_num = sizeof(servo_port) / sizeof(servo_port[0]); //定义舵机数量
float value_init[8] = {1294,1132,1422,1651,1680,1507,930,1314}; //定义舵机初始角度
enum{WalkForward=1,DogLeft,DogRight,DogDance,DogReset};
int Judge=0;
int GetIntData=0;
int GetSensorValue[2]={0,0};
void setup() {
Serial.begin(9600);//波特率
for(int i=0;i<sensornum;i++)
{pinMode(sensorpin[i],INPUT);}//传感器设置为输入模式
for(int i=0;i<servo_num;i++){
ServoGo(i,value_init[i]);}//使能舵机并赋予初始角度
delay(2000);
Serial.println("begin");
}
void loop() {
switch(get_sensor_data())//判断传感器不同状态小狗的状态
{
case 1: DogActionRight();break;
case 2: DogActionLeft();break;
case 3: DogActionWalk_Back();break;
case 4: DogActionWalk_Forward();break;
default: break;
}
}
int get_sensor_data()//获得传感器状态
{
for(int i=0;i<sensornum;i++)
{
GetSensorValue[i]=!digitalRead(sensorpin[i]);
}
if( (GetSensorValue[0] == 1)&&(GetSensorValue[1] == 0) ){return 1;}
else if( (GetSensorValue[0] == 0)&&(GetSensorValue[1] == 1) ){return 2;}
else if( (GetSensorValue[0] == 1)&&(GetSensorValue[1] == 1) ){return 3;}
else { return 4; }
}
void DogActionWalk_Forward()//小狗前进时的舵机动作
{
servo_move(1294,1132,1522,1651,1780,1497,930,1314, SERVO_SPEED_WalkForward_low); //初始化状态
servo_move(1394,1042,1452,1751,1680,1507,860,1214, SERVO_SPEED_WalkForward_low); //右脚向后缩,左脚向前伸
servo_move(1394,1182,1517,1615,1680,1563,900,1214, SERVO_SPEED_WalkForward_high); //快速左脚向前极限
}
void DogActionWalk_Back(){//小狗后退时的舵机动作
//three
servo_move(1294,1143,1441,1829,1580,1559,913,1314, SERVO_SPEED_WalkBack_low); //右脚在后,
servo_move(1194,1161,1441,1729,1680,1469,824,1414, SERVO_SPEED_WalkBack_low); //左脚向前,右脚向后
servo_move(1194,1261,1463,1729,1680,1581,910,1414, SERVO_SPEED_WalkBack_high); //
}
void DogActionReset(){
servo_move(1294,1132,1422,1651,1680,1507,930,1314,SERVO_SPEED); //初始化
}
void DogActionLeft(){//小狗左转时的舵机动作
servo_move(1111,1030,1621,1700,1740,1647,910,1154, SERVO_SPEED); //
servo_move(1211,1030,1650,1655,1695,1697,910,1254, SERVO_SPEED); //左前脚向前,右后脚向后
servo_move(1311,1030,1609,1600,1595,1697,887,1354, SERVO_SPEED); //左前脚向前到极限角度,右后脚向内缩到极限
servo_move(1311,963,1579,1600,1595,1647,730,1354, SERVO_SPEED1); //【快速?】
servo_move(1111,1075,1579,1600,1595,1647,859,1154, SERVO_SPEED1); //左前脚向后缩到极限,右后脚向前缩到极限
}
void DogActionRight(){//小狗右转时的舵机动作
servo_move(1194,1120,1589,1739,1680,1585,871,1214, SERVO_SPEED_Right_low); // 右脚向后缩,左脚也向后缩
servo_move(1094,1110,1569,1839,1780,1565,936,1114, SERVO_SPEED_Right_low); //左前脚向后缩到极限,右后脚向前缩到极限
servo_move(1394,885,1509,1839,1780,1505,843,1414, SERVO_SPEED_Right_high); //【快速?】左前脚向前伸到极限,
servo_move(1294,995,1552,1839,1780,1547,843,1314, SERVO_SPEED_Right_low); //左腿向后缩,右腿不动
servo_move(1294,1015,1597,1639,1580,1617,843,1314, SERVO_SPEED_Right_high); //
}
void ServoStart(int which)//使能舵机
{
if(!myServo[which].attached())myServo[which].attach(servo_port[which]);
pinMode(servo_port[which], OUTPUT);
}
void ServoStop(int which)//释放舵机
{
myServo[which].detach();
digitalWrite(servo_port[which],LOW);
}
void ServoGo(int which , int where)//打开并给舵机写入相关角度
{
if(where!=200)
{
if(where==201) ServoStop(which);
else
{
ServoStart(which);
myServo[which].write(map(where,500,2500,0,180));
}
}
}
void servo_move(float value0, float value1, float value2, float value3, float value4, float value5,float value6,float value7,float t)
{
float value_arguments[] = {value0, value1, value2, value3, value4, value5,value6,value7};
float value_delta[servo_num];
for(int i=0;i<servo_num;i++)
{
value_delta[i] = (value_arguments[i] - value_init[i]) / f;
}
for(int i=0;i<f;i++)
{
for(int k=0;k<servo_num;k++)
{
value_init[k] = value_delta[k] == 0 ? value_arguments[k] : value_init[k] + value_delta[k];
}
for(int j=0;j<servo_num;j++)
{
ServoGo(j,value_init[j]);
}
delay(t);
}
}