1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217
|
#include <ax12.h> //Include ArbotiX DYNAMIXEL library
const int SERVO_ID[] = {1, 2, 3, 4};
const int servo_count = sizeof(SERVO_ID) / sizeof(*SERVO_ID);
int repetitions;
double Speed;
int m = 100; //columns
int pos2[] = {1750, 400, 1500, 1330}; //rest position of the dynamixel motors
#include <SPI.h>
#include <SD.h>
File myFile;
void setup()
{
dxlInit(1000000); //start dynamixel library at 1mbps to communicate with the servos
Serial.begin(9600); //start serial at 9600 for reporting data.
for (int i = 0; i < servo_count; ++i)
{
Relax(SERVO_ID[i]);
Serial.print(F("ID: "));
Serial.println(SERVO_ID[i]);
}
Serial.print("Iniciando SD ...");
if (!SD.begin(4)) {
Serial.println("No se pudo inicializar");
return;
}
Serial.println("inicializacion exitosa");
delay(1000);
}
void loop()
{
Serial.println(F("How many times do you want to repeat the sequence?"));
while (Serial.available() == 0) {}
repetitions = Serial.parseInt();
Serial.print(F("repetitions = "));
Serial.println(repetitions);
delay(3000);
Serial.println(F("How fast do you want to repeat the sequence?"));
Serial.println(F(" 1 = Slow 2 = Normal 3 = Fast"));
while (Serial.available() == 0) {}
Speed = Serial.parseInt();
if (Speed <= 0 || Speed >= 4)
{
Serial.println(F("You have entered a wrong value"));
return;
}
if (Speed == 1)
{
Speed = 1000;
}
else if (Speed == 2)
{
Speed = 700;
}
else if (Speed == 3)
{
Speed = 400;
}
Serial.print(F("Speed = "));
Serial.print(Speed, 0);
Serial.println(F(" microseconds"));
delay(3000);
Serial.print(F("Positions vector "));
Serial.print(F(": ["));
int positionn[servo_count][m]; //Matrix of movements
String dataString = ""; //vacia el string para evitar problemas
myFile[servo_count] = { SD.open("Prueba0.txt", FILE_WRITE), SD.open("Prueba1.txt", FILE_WRITE), SD.open("Prueba2.txt", FILE_WRITE), SD.open("Prueba3.txt", FILE_WRITE)};
for(const File &f : myFile)
{
if(f)
Serial.println("file is open");
else
Serial.println("Error opening the file");
}
for (int i = 0; i < m; i++) // structure to create columns
{
for (int j = 0; j < servo_count; j++) // structure to create columns
{
int pos = dxlGetPosition(SERVO_ID[j]);
myFile[j].println(pos); //read and save the actual position
Serial.print(pos); //Display the vector
Serial.print(F(", "));
}
delay(10);
}
Serial.print(F("]\n"));
delay(5000);
myFile.close(); //close the file
Serial.println(F("The servos will move to the initial position."));
/***The servos will move according to registered movements***/
myFile[servo_count] = { SD.open("Prueba0.txt", FILE_READ), SD.open("Prueba1.txt", FILE_READ), SD.open("Prueba2.txt", FILE_READ), SD.open("Prueba3.txt", FILE_READ)};
for (int a = 0; a < repetitions; a++) //Repetition of the process (a = number of sequences)
{
Serial.print(F("SEQUENCE "));
Serial.println(a + 1);
int pos_from_file[servo_count]; // Note
int position[servo_count];
int turns[servo_count];
int pos1[servo_count];
int pos2[servo_count];
int current[servo_count];
for (int i = 0; i < servo_count; i++)
{
pos_from_file[i] = myFile[i].parseInt(); // Note
current[i] = pos_from_file[i];
position[i] = current[i];
turns[i] = 0;
pos1[i] = dxlGetPosition(SERVO_ID[i]); //Actual servo position
pos2[i] = position[i]; //Initial position of the movement (objective)
}
for (int servo = 0; servo < servo_count; ++servo)
{
go_to_position(pos1, pos2, servo); //Function that moves the robot to the initial position
}
Serial.println(F("Now the servos will do the registered movements."));
delay(2000);
for (int movement = 0; movement < m; movement++)
{
for (int servo = 0; servo < servo_count; servo++)
{
if (pos_from_file[servo] != current[servo])
{
int next_pos = 1;
if (pos_from_file[servo] < current[servo]) // Note
next_pos = -1;
while (pos_from_file[servo] != current[servo]) // Note
{
dxlSetGoalPosition(SERVO_ID[servo], current[servo]);
current[servo] += next_pos;
delayMicroseconds(Speed);
if (current[servo] == position[servo] + MX_MAX_POSITION_VALUE)
{
position[servo] = current[servo];
turns[servo]++;
}
else if (current[servo] == position[servo] - MX_MAX_POSITION_VALUE)
{
position[servo] = current[servo];
turns[servo]--;
}
}
}
pos_from_file[servo] = myFile[servo].parseInt();
}
}
for (int i = 0; i < servo_count; i++)
{
Serial.print(F("Turns engine "));
Serial.print(i + 1);
Serial.print(F(": "));
Serial.println(turns[i]);
Serial.println(" ");
}
}
myFile.close(); //close the file
delay(3000);
/****REST POSITION****/
Serial.println(F("The robot will move to the resting position."));
int pos1[servo_count];
for (int i = 0; i < servo_count; i++)
{
pos1[i] = dxlGetPosition(SERVO_ID[i]); //Actual servo position
}
for (int servo = 0; servo < servo_count; ++servo)
{
go_to_position(pos1, pos2, servo); //Function that moves the robot to the initial position
}
delay(1000);
dxlTorqueOffAll();
Serial.println(F("END!"));
}
void go_to_position(int pos1[], int pos2[], int servo)//function
{
while (pos1[servo] != pos2[servo])
{
if (pos2[servo] < pos1[servo])
{
dxlSetGoalPosition(SERVO_ID[servo], pos1[servo]);
pos1[servo]--;
delayMicroseconds(800);
}
else if (pos2[servo] > pos1[servo])
{
dxlSetGoalPosition(SERVO_ID[servo], pos1[servo]);
pos1[servo]++;
delayMicroseconds(800);
}
}
}
| |