-
Notifications
You must be signed in to change notification settings - Fork 6
/
robot_control.ino
129 lines (117 loc) · 2.71 KB
/
robot_control.ino
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
#include <Servo.h>
// Declare the Arduino pin where each servo is connected
#define SERVO_BASE_PIN 8
#define SERVO_SHOULDER_PIN 9
#define SERVO_ELBOW_PIN 10
#define SERVO_GRIPPER_PIN 11
// Define the start configuration of the joints
#define BASE_START 90
#define SHOULDER_START 90
#define ELBOW_START 90
#define GRIPPER_START 0
// Register the servo motors of each joint
Servo base;
Servo shoulder;
Servo elbow;
Servo gripper;
uint8_t idx = 0;
uint8_t val_idx = 0;
char value[4] = "000";
/*
* This function moves a given servo smoothly from a given start position to a given end position.
* The movement can be both clockwise or counterclockwise based on the values assigned to
* the start position and end position
*/
void reach_goal(Servo& motor, int goal){
if(goal>=motor.read()){
// goes from the start point degrees to the end point degrees
for (int pos = motor.read(); pos <= goal; pos += 1) {
motor.write(pos);
delay(5);
}
} else{
// goes from the end point degrees to the start point degrees
for (int pos = motor.read(); pos >= goal; pos -= 1) {
motor.write(pos);
delay(5);
}
}
}
void setup() {
// Attach and Initialize each Servo to the Arduino pin where it is connected
base.attach(SERVO_BASE_PIN);
shoulder.attach(SERVO_SHOULDER_PIN);
elbow.attach(SERVO_ELBOW_PIN);
gripper.attach(SERVO_GRIPPER_PIN);
// Set a common start point for each joint
// This way, the start status of each joint is known
base.write(BASE_START);
shoulder.write(SHOULDER_START);
elbow.write(ELBOW_START);
gripper.write(GRIPPER_START);
// Start the Serial communication with ROS
Serial.begin(115200);
Serial.setTimeout(1);
}
void loop() {
if (Serial.available())
{
char chr = Serial.read();
// base motor
if(chr == 'b')
{
idx = 0;
val_idx = 0;
}
// shoulder motor
else if(chr == 's')
{
idx = 1;
val_idx = 0;
}
// elbow motor
else if(chr == 'e')
{
idx = 2;
val_idx = 0;
}
// gripper motor
else if(chr == 'g')
{
idx = 3;
val_idx = 0;
}
// Separator
else if(chr == ',')
{
int val = atoi(value);
if(idx == 0)
{
reach_goal(base, val);
}
else if(idx == 1)
{
reach_goal(shoulder, val);
}
else if(idx == 2)
{
reach_goal(elbow, val);
}
else if(idx == 3)
{
reach_goal(gripper, val);
}
// reset the angle
value[0] = '0';
value[1] = '0';
value[2] = '0';
value[3] = '\0';
}
// Plain number
else
{
value[val_idx] = chr;
val_idx++;
}
}
}