9
9
10
10
This library is distributed in the hope that it will be useful,
11
11
but WITHOUT ANY WARRANTY; without even the implied warranty of
12
- MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
12
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
13
13
Lesser General Public License for more details.
14
14
15
15
You should have received a copy of the GNU Lesser General Public
16
16
License along with this library; if not, write to the Free Software
17
- Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
17
+ Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
18
18
*/
19
19
20
20
#include " Braccio.h"
@@ -32,7 +32,7 @@ extern int step_elbow = 180;
32
32
extern int step_wrist_rot = 180 ;
33
33
extern int step_wrist_ver = 90 ;
34
34
extern int step_gripper = 10 ;
35
-
35
+
36
36
37
37
_Braccio Braccio;
38
38
@@ -43,8 +43,8 @@ _Braccio::_Braccio() {
43
43
/* *
44
44
* Braccio initialization and set intial position
45
45
* Modifing this function you can set up the initial position of all the
46
- * servo motors of Braccio
47
- * @param soft_start_level: from -10 to +10, default value is 0 (SOFT_START_DEFAULT)
46
+ * servo motors of Braccio
47
+ * @param soft_start_level: default value is 0 (SOFT_START_DEFAULT)
48
48
* You should set begin(SOFT_START_DISABLED) if you are using the Arm Robot shield V1.6
49
49
* SOFT_START_DISABLED disable the Braccio movements
50
50
*/
@@ -62,8 +62,8 @@ unsigned int _Braccio::begin(int soft_start_level) {
62
62
wrist_rot.attach (6 );
63
63
wrist_ver.attach (5 );
64
64
gripper.attach (3 );
65
-
66
- // For each step motor this set up the initial degree
65
+
66
+ // For each step motor this set up the initial degree
67
67
base.write (0 );
68
68
shoulder.write (40 );
69
69
elbow.write (180 );
@@ -78,9 +78,8 @@ unsigned int _Braccio::begin(int soft_start_level) {
78
78
step_wrist_rot = 0 ;
79
79
step_gripper = 73 ;
80
80
81
-
82
81
if (soft_start_level!=SOFT_START_DISABLED)
83
- _softStart (soft_start_level);
82
+ _softStart (soft_start_level);
84
83
return 1 ;
85
84
}
86
85
@@ -93,29 +92,29 @@ void _Braccio::_softwarePWM(int high_time, int low_time){
93
92
digitalWrite (SOFT_START_CONTROL_PIN,HIGH);
94
93
delayMicroseconds (high_time);
95
94
digitalWrite (SOFT_START_CONTROL_PIN,LOW);
96
- delayMicroseconds (low_time);
95
+ delayMicroseconds (low_time);
97
96
}
98
97
99
98
/*
100
99
* This function, used only with the Braccio Shield V4 and greater,
101
100
* turn ON the Braccio softly and save it from brokes.
102
101
* The SOFT_START_CONTROL_PIN is used as a software PWM
103
- * @param soft_start_level: from -10 to +10 , default value is 0 (SOFT_START_DEFAULT)
102
+ * @param soft_start_level: the minimum value is -70 , default value is 0 (SOFT_START_DEFAULT)
104
103
*/
105
- void _Braccio::_softStart (int soft_start_level){
104
+ void _Braccio::_softStart (int soft_start_level){
106
105
long int tmp=millis ();
107
106
while (millis ()-tmp < LOW_LIMIT_TIMEOUT)
108
- _softwarePWM (30 +soft_start_level, 500 - soft_start_level);
107
+ _softwarePWM (80 +soft_start_level, 450 - soft_start_level); // the sum should be 530usec
109
108
110
109
while (millis ()-tmp < HIGH_LIMIT_TIMEOUT)
111
- _softwarePWM (25 + soft_start_level, 480 - soft_start_level);
110
+ _softwarePWM (75 + soft_start_level, 430 - soft_start_level); // the sum should be 505usec
112
111
113
112
digitalWrite (SOFT_START_CONTROL_PIN,HIGH);
114
113
}
115
114
116
115
/* *
117
116
* This functions allow you to control all the servo motors
118
- *
117
+ *
119
118
* @param stepDelay The delay between each servo movement
120
119
* @param vBase next base servo motor degree
121
120
* @param vShoulder next shoulder servo motor degree
@@ -127,7 +126,7 @@ void _Braccio::_softStart(int soft_start_level){
127
126
int _Braccio::ServoMovement (int stepDelay, int vBase, int vShoulder, int vElbow,int vWrist_ver, int vWrist_rot, int vgripper) {
128
127
129
128
// Check values, to avoid dangerous positions for the Braccio
130
- if (stepDelay > 30 ) stepDelay = 30 ;
129
+ if (stepDelay > 30 ) stepDelay = 30 ;
131
130
if (stepDelay < 10 ) stepDelay = 10 ;
132
131
if (vBase < 0 ) vBase=0 ;
133
132
if (vBase > 180 ) vBase=180 ;
@@ -139,17 +138,17 @@ int _Braccio::ServoMovement(int stepDelay, int vBase, int vShoulder, int vElbow,
139
138
if (vWrist_ver > 180 ) vWrist_ver=180 ;
140
139
if (vWrist_rot > 180 ) vWrist_rot=180 ;
141
140
if (vWrist_rot < 0 ) vWrist_rot=0 ;
142
- if (vgripper < 10 ) vgripper = 10 ;
141
+ if (vgripper < 10 ) vgripper = 10 ;
143
142
if (vgripper > 73 ) vgripper = 73 ;
144
143
145
144
int exit = 1 ;
146
145
147
146
// Until the all motors are in the desired position
148
- while (exit)
149
- {
150
- // For each servo motor if next degree is not the same of the previuos than do the movement
151
- if (vBase != step_base)
152
- {
147
+ while (exit)
148
+ {
149
+ // For each servo motor if next degree is not the same of the previuos than do the movement
150
+ if (vBase != step_base)
151
+ {
153
152
base.write (step_base);
154
153
// One step ahead
155
154
if (vBase > step_base) {
@@ -161,7 +160,7 @@ int _Braccio::ServoMovement(int stepDelay, int vBase, int vShoulder, int vElbow,
161
160
}
162
161
}
163
162
164
- if (vShoulder != step_shoulder)
163
+ if (vShoulder != step_shoulder)
165
164
{
166
165
shoulder.write (step_shoulder);
167
166
// One step ahead
@@ -175,7 +174,7 @@ int _Braccio::ServoMovement(int stepDelay, int vBase, int vShoulder, int vElbow,
175
174
176
175
}
177
176
178
- if (vElbow != step_elbow)
177
+ if (vElbow != step_elbow)
179
178
{
180
179
elbow.write (step_elbow);
181
180
// One step ahead
@@ -189,12 +188,12 @@ int _Braccio::ServoMovement(int stepDelay, int vBase, int vShoulder, int vElbow,
189
188
190
189
}
191
190
192
- if (vWrist_ver != step_wrist_rot)
191
+ if (vWrist_ver != step_wrist_rot)
193
192
{
194
193
wrist_rot.write (step_wrist_rot);
195
194
// One step ahead
196
195
if (vWrist_ver > step_wrist_rot) {
197
- step_wrist_rot++;
196
+ step_wrist_rot++;
198
197
}
199
198
// One step beyond
200
199
if (vWrist_ver < step_wrist_rot) {
@@ -227,11 +226,11 @@ int _Braccio::ServoMovement(int stepDelay, int vBase, int vShoulder, int vElbow,
227
226
step_gripper--;
228
227
}
229
228
}
230
-
229
+
231
230
// delay between each movement
232
231
delay (stepDelay);
233
-
234
- // It checks if all the servo motors are in the desired position
232
+
233
+ // It checks if all the servo motors are in the desired position
235
234
if ((vBase == step_base) && (vShoulder == step_shoulder)
236
235
&& (vElbow == step_elbow) && (vWrist_ver == step_wrist_rot)
237
236
&& (vWrist_rot == step_wrist_ver) && (vgripper == step_gripper)) {
0 commit comments