dimamichev писал(а):А дальше всё?
Ты уже перерос такие игрушки. Надо замахиваться на большой проект!
roboforum.ruТехнический форум по робототехнике. |
|
|
|
dimamichev писал(а):А дальше всё?
Реклама | ||||
|
|
|||
Реклама | ||||
|
|
|||
dimamichev писал(а):Только получается это 3 уровень, выбор сценария из имеющихся.
Scorpio писал(а):Не, выбор - это скучно. Твое создание должно генерировать новые действия и умения, которые, ты в него не закладывал. В примере с пауком, он будет генерировать позы (случайное сочетание положений серв с некоторыми ограничениями)
////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
//
// Arduino UNO,Pro mini
//
////////////////////////
//ПАУК (ГЕКСАПОД) 3 СЕРВОПРИВОДА с датчиком
//
#include <Servo.h>
byte dd=10;//амплитуда ходьбы
byte n=5;// постоянная временного интервала
byte i=0;//счётчик
byte j=0;//счётчик
byte a=90;//угол "серединный"
byte b=90;//угол "серединный"
byte c=95;//угол "серединный"
boolean fl_A=false;//флаг состояний
long Y=0;//переменная хранения моментов времени
////////////////////////////
Servo servo_a;
Servo servo_b;
Servo servo_c;
void setup()
{
servo_a.attach(5);//вывод управления сервоприводом ПРАВАЯ ПАРА
servo_a.write(a+dd);// установка начального значения
servo_b.attach(6);//вывод управления сервоприводом ЛЕВАЯ ПАРА
servo_b.write(b+dd);// установка начального значения
servo_c.attach(7);//вывод управления сервоприводом ЦЕНТРАЛЬНАЯ ПАРА
servo_c.write(c-dd);// установка начального значения
pinMode (8,INPUT );//подключение датчика препятствий
}
/////////////////////////////////////////////////////////////////////////////////////////
void loop()
{
//////////// СЦЕНАРИЙ ПОВЕДЕНИЯ ГЕКСАПОДА //////////////////////
if(fl_A==true){vpered(2);vilanie_2(10);nazad(7);if(random(0,2)==1){levo(5);}else{pravo(5);}}//если на пути преграда пытаемся сдвинуть-пройти,отходим,разворачиваемся
if(fl_A==false){vpered(1);}//если преграды нет идём прямо
}
/////////////////////////////////////////////////////////////////////////////////////////
void vpered(byte k){
for(j=0;j<k;j++){
///////////// ВПЕРЁД /////////////
servo_c.write(c-dd);// установка начального значения
servo_a.write(a+dd);// установка начального значения
servo_b.write(b+dd);// установка начального значения
/////////// такт 1 ///////////
for(i=0;i<2*dd;i++)
{
servo_a.write(servo_a.read()-1);
servo_b.write(servo_b.read()-1);
delay_(n);
}
/////////// такт 2 ///////////
for(i=0;i<2*dd;i++)
{
servo_c.write(servo_c.read()+1);
delay_(n);
}
/////////// такт 3 ///////////
for(i=0;i<2*dd;i++)
{
servo_a.write(servo_a.read()+1);
servo_b.write(servo_b.read()+1);
delay_(n);
}
/////////// такт 4 ///////////
for(i=0;i<2*dd;i++)
{
servo_c.write(servo_c.read()-1);
delay_(n);
}
}
}
///////////////////////////////////////////////////////////////////////////////////////
/////////////////////////////////////////////////////////////////////////////////////////
void levo(byte k){
for(j=0;j<k;j++){
///////////// ВЛЕВО /////////////
servo_c.write(c-dd);// установка начального значения
servo_a.write(a+dd);// установка начального значения
servo_b.write(b-dd);// установка начального значения
/////////// такт 1 ///////////
for(i=0;i<2*dd;i++)
{
servo_a.write(servo_a.read()-1);
servo_b.write(servo_b.read()+1);
delay_(n);
}
/////////// такт 2 ///////////
for(i=0;i<2*dd;i++)
{
servo_c.write(servo_c.read()+1);
delay_(n);
}
/////////// такт 3 ///////////
for(i=0;i<2*dd;i++)
{
servo_a.write(servo_a.read()+1);
servo_b.write(servo_b.read()-1);
delay_(n);
}
/////////// такт 4 ///////////
for(i=0;i<2*dd;i++)
{
servo_c.write(servo_c.read()-1);
delay_(n);
}
}
}
///////////////////////////////////////////////////////////////////////////////////////////
void pravo(byte k){
for(j=0;j<k;j++){
///////////// ВПРАВО /////////////
servo_c.write(c-dd);// установка начального значения
servo_a.write(a-dd);// установка начального значения
servo_b.write(b+dd);// установка начального значения
/////////// такт 1 ///////////
for(i=0;i<2*dd;i++)
{
servo_a.write(servo_a.read()+1);
servo_b.write(servo_b.read()-1);
delay_(n);
}
/////////// такт 2 ///////////
for(i=0;i<2*dd;i++)
{
servo_c.write(servo_c.read()+1);
delay_(n);
}
/////////// такт 3 ///////////
for(i=0;i<2*dd;i++)
{
servo_a.write(servo_a.read()-1);
servo_b.write(servo_b.read()+1);
delay_(n);
}
/////////// такт 4 ///////////
for(i=0;i<2*dd;i++)
{
servo_c.write(servo_c.read()-1);
delay_(n);
}
}
}
///////////////////////////////////////////////////////////////////////////////////////////
void na_meste(byte k){
for(j=0;j<k;j++){
///////////// ТОПТАНИЕ НА МЕСТЕ /////////////
servo_c.write(c-dd);// установка начального значения
/////////// такт 1 ///////////
for(i=0;i<2*dd;i++)
{
servo_c.write(servo_c.read()+1);
delay_(2*n);
}
/////////// такт 2 ///////////
for(i=0;i<2*dd;i++)
{
servo_c.write(servo_c.read()-1);
delay_(2*n);
}
}
}
///////////////////////////////////////////////////////////////////////////////////////////
void vilanie_2(byte k){
for(j=0;j<k;j++){
///////////// ВИЛЯНИЕ ТУШКОЙ 2 /////////////
servo_c.write(c-dd);// установка начального значения
servo_a.write(a+dd);// установка начального значения
servo_b.write(b+dd);// установка начального значения
/////////// такт 1 ///////////
for(i=0;i<2*dd;i++)
{
servo_a.write(servo_a.read()-1);
delay(n);
}
/////////// такт 2 ///////////
for(i=0;i<2*dd;i++)
{
servo_a.write(servo_a.read()+1);
delay(n);
}
}
}
///////////////////////////////////////////////////////////////////////////////////////
void nazad(byte k){
for(j=0;j<k;j++){
///////////// НАЗАД /////////////
servo_c.write(c+dd);// установка начального значения
servo_a.write(a+dd);// установка начального значения
servo_b.write(b+dd);// установка начального значения
/////////// такт 1 ///////////
for(i=0;i<2*dd;i++)
{
servo_a.write(servo_a.read()-1);
servo_b.write(servo_b.read()-1);
delay(n);
}
/////////// такт 2 ///////////
for(i=0;i<2*dd;i++)
{
servo_c.write(servo_c.read()-1);
delay(n);
}
/////////// такт 3 ///////////
for(i=0;i<2*dd;i++)
{
servo_a.write(servo_a.read()+1);
servo_b.write(servo_b.read()+1);
delay(n);
}
/////////// такт 4 ///////////
for(i=0;i<2*dd;i++)
{
servo_c.write(servo_c.read()+1);
delay(n);
}
}
}
/////////////////////////////////////////////////////////////////////////////////////////
///////////////////////////////////////////////////////////////////////////////////////
//// ФУНКЦИИ ОПИСАНИЕ // вместо задержки времени через delay ////////////////////////////////////////
void delay_(int T1)
{
Y=millis();
while(millis()-Y<T1)
{
if(digitalRead(8)==LOW){fl_A=true;}else{fl_A=false;}
}
}
///////////////////////////////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
//
// Arduino UNO,Pro mini
//
////////////////////////
//ПАУК (ГЕКСАПОД) 3 СЕРВОПРИВОДА ТЕСТ
//
#include <Servo.h>
byte dd=10;//амплитуда ходьбы
byte n=5;// постоянная временного интервала
byte i=0;//счётчик
byte j=0;//счётчик
byte a=90;//угол "серединный"
byte b=90;//угол "серединный"
byte c=98;//угол "серединный"
long Y=0;//переменная хранения моментов времени
int tabl[]={-4*dd/5,-3*dd/5,-2*dd/5,-dd/5,0,dd/5,2*dd/5,3*dd/5,4*dd/5,dd,dd,dd,dd,dd,dd,dd,dd,dd,dd,dd,
4*dd/5,3*dd/5,2*dd/5,dd/5,0,-dd/5,-2*dd/5,-3*dd/5,-4*dd/5,-dd,-dd,-dd,-dd,-dd,-dd,-dd,-dd,-dd,-dd,-dd};//массив последовательности приращений углов
int DL = sizeof(tabl) / sizeof(tabl[0]);//количество элементов массива
byte sm_1=DL/4;//смещение последовательности приращений углов ВПЕРЁД(sm_1=DL/4,sm_2=0);НАЗАД(sm_1=3*DL/4,sm_2=0)
byte sm_2=0;//смещение последовательности приращений углов ВПРАВО(sm_1=DL/4,sm_2=DL/2);ВЛЕВО(sm_1=3*DL/4,sm_2=DL/2)
////////////////////////////
Servo servo_a;
Servo servo_b;
Servo servo_c;
void setup()
{
servo_a.attach(5);//вывод управления сервоприводом ПРАВАЯ ПАРА
servo_a.write(a);// установка начального значения
servo_b.attach(6);//вывод управления сервоприводом ЛЕВАЯ ПАРА
servo_b.write(b);// установка начального значения
servo_c.attach(7);//вывод управления сервоприводом ЦЕНТРАЛЬНАЯ ПАРА
servo_c.write(c);// установка начального значения
}
/////////////////////////////////////////////////////////////////////////////////////////
void loop()
{
dvig();
}
/////////////////////////////////////////////////////////////////////////////////////////
void dvig(){
for(i=0;i<DL;i++)
{
if(i+sm_2>=DL){servo_a.write(a+tabl[i+sm_2-DL]);}else{servo_a.write(a+tabl[i+sm_2]);}
servo_b.write(b+tabl[i]);
if(i+sm_1>=DL){servo_c.write(c+tabl[i+sm_1-DL]);}else{servo_c.write(c+tabl[i+sm_1]);}
delay_(2*n);
}
}
///////////////////////////////////////////////////////////////////////////////////////
//// ФУНКЦИИ ОПИСАНИЕ // вместо задержки времени через delay ////////////////////////////////////////
void delay_(int T1)
{
Y=millis();
while(millis()-Y<T1)
{
///////////
}
}
////////////////////////////////////////////////////////////////////
Вернуться в Arduino и другие Xduino
Сейчас этот форум просматривают: нет зарегистрированных пользователей и гости: 2