Skip to content
This repository was archived by the owner on Feb 21, 2020. It is now read-only.

Commit 59e6f25

Browse files
Merge branch 'dev'
2 parents d62dbb0 + 0eb245b commit 59e6f25

File tree

3 files changed

+32
-33
lines changed

3 files changed

+32
-33
lines changed

library.properties

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,5 @@
11
name=Braccio
2-
version=2.0
2+
version=2.0.1
33
author=Andrea Martino
44
maintainer=Andrea <[email protected]>
55
sentence=For Arduino braccio only.

src/Braccio.cpp

Lines changed: 28 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -9,12 +9,12 @@
99
1010
This library is distributed in the hope that it will be useful,
1111
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
1313
Lesser General Public License for more details.
1414
1515
You should have received a copy of the GNU Lesser General Public
1616
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
1818
*/
1919

2020
#include "Braccio.h"
@@ -32,7 +32,7 @@ extern int step_elbow = 180;
3232
extern int step_wrist_rot = 180;
3333
extern int step_wrist_ver = 90;
3434
extern int step_gripper = 10;
35-
35+
3636

3737
_Braccio Braccio;
3838

@@ -43,8 +43,8 @@ _Braccio::_Braccio() {
4343
/**
4444
* Braccio initialization and set intial position
4545
* 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)
4848
* You should set begin(SOFT_START_DISABLED) if you are using the Arm Robot shield V1.6
4949
* SOFT_START_DISABLED disable the Braccio movements
5050
*/
@@ -62,8 +62,8 @@ unsigned int _Braccio::begin(int soft_start_level) {
6262
wrist_rot.attach(6);
6363
wrist_ver.attach(5);
6464
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
6767
base.write(0);
6868
shoulder.write(40);
6969
elbow.write(180);
@@ -78,9 +78,8 @@ unsigned int _Braccio::begin(int soft_start_level) {
7878
step_wrist_rot = 0;
7979
step_gripper = 73;
8080

81-
8281
if(soft_start_level!=SOFT_START_DISABLED)
83-
_softStart(soft_start_level);
82+
_softStart(soft_start_level);
8483
return 1;
8584
}
8685

@@ -93,29 +92,29 @@ void _Braccio::_softwarePWM(int high_time, int low_time){
9392
digitalWrite(SOFT_START_CONTROL_PIN,HIGH);
9493
delayMicroseconds(high_time);
9594
digitalWrite(SOFT_START_CONTROL_PIN,LOW);
96-
delayMicroseconds(low_time);
95+
delayMicroseconds(low_time);
9796
}
9897

9998
/*
10099
* This function, used only with the Braccio Shield V4 and greater,
101100
* turn ON the Braccio softly and save it from brokes.
102101
* 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)
104103
*/
105-
void _Braccio::_softStart(int soft_start_level){
104+
void _Braccio::_softStart(int soft_start_level){
106105
long int tmp=millis();
107106
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
109108

110109
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
112111

113112
digitalWrite(SOFT_START_CONTROL_PIN,HIGH);
114113
}
115114

116115
/**
117116
* This functions allow you to control all the servo motors
118-
*
117+
*
119118
* @param stepDelay The delay between each servo movement
120119
* @param vBase next base servo motor degree
121120
* @param vShoulder next shoulder servo motor degree
@@ -127,7 +126,7 @@ void _Braccio::_softStart(int soft_start_level){
127126
int _Braccio::ServoMovement(int stepDelay, int vBase, int vShoulder, int vElbow,int vWrist_ver, int vWrist_rot, int vgripper) {
128127

129128
// Check values, to avoid dangerous positions for the Braccio
130-
if (stepDelay > 30) stepDelay = 30;
129+
if (stepDelay > 30) stepDelay = 30;
131130
if (stepDelay < 10) stepDelay = 10;
132131
if (vBase < 0) vBase=0;
133132
if (vBase > 180) vBase=180;
@@ -139,17 +138,17 @@ int _Braccio::ServoMovement(int stepDelay, int vBase, int vShoulder, int vElbow,
139138
if (vWrist_ver > 180) vWrist_ver=180;
140139
if (vWrist_rot > 180) vWrist_rot=180;
141140
if (vWrist_rot < 0) vWrist_rot=0;
142-
if (vgripper < 10) vgripper = 10;
141+
if (vgripper < 10) vgripper = 10;
143142
if (vgripper > 73) vgripper = 73;
144143

145144
int exit = 1;
146145

147146
//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+
{
153152
base.write(step_base);
154153
//One step ahead
155154
if (vBase > step_base) {
@@ -161,7 +160,7 @@ int _Braccio::ServoMovement(int stepDelay, int vBase, int vShoulder, int vElbow,
161160
}
162161
}
163162

164-
if (vShoulder != step_shoulder)
163+
if (vShoulder != step_shoulder)
165164
{
166165
shoulder.write(step_shoulder);
167166
//One step ahead
@@ -175,7 +174,7 @@ int _Braccio::ServoMovement(int stepDelay, int vBase, int vShoulder, int vElbow,
175174

176175
}
177176

178-
if (vElbow != step_elbow)
177+
if (vElbow != step_elbow)
179178
{
180179
elbow.write(step_elbow);
181180
//One step ahead
@@ -189,12 +188,12 @@ int _Braccio::ServoMovement(int stepDelay, int vBase, int vShoulder, int vElbow,
189188

190189
}
191190

192-
if (vWrist_ver != step_wrist_rot)
191+
if (vWrist_ver != step_wrist_rot)
193192
{
194193
wrist_rot.write(step_wrist_rot);
195194
//One step ahead
196195
if (vWrist_ver > step_wrist_rot) {
197-
step_wrist_rot++;
196+
step_wrist_rot++;
198197
}
199198
//One step beyond
200199
if (vWrist_ver < step_wrist_rot) {
@@ -227,11 +226,11 @@ int _Braccio::ServoMovement(int stepDelay, int vBase, int vShoulder, int vElbow,
227226
step_gripper--;
228227
}
229228
}
230-
229+
231230
//delay between each movement
232231
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
235234
if ((vBase == step_base) && (vShoulder == step_shoulder)
236235
&& (vElbow == step_elbow) && (vWrist_ver == step_wrist_rot)
237236
&& (vWrist_rot == step_wrist_ver) && (vgripper == step_gripper)) {

src/Braccio.h

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -45,8 +45,8 @@ class _Braccio {
4545
/**
4646
* Braccio initializations and set intial position
4747
* Modifing this function you can set up the initial position of all the
48-
* servo motors of the Braccio
49-
*@param soft_start_level: from -10 to +10, default value is 0 (SOFT_START_DEFAULT)
48+
* servo motors of Braccio
49+
*@param soft_start_level: the minimum value is -70, default value is 0 (SOFT_START_DEFAULT)
5050
* You should set begin(SOFT_START_DISABLED) if you are using the Arm Robot shield V1.6
5151
*/
5252
unsigned int begin(int soft_start_level=SOFT_START_DEFAULT);
@@ -62,7 +62,7 @@ class _Braccio {
6262
* This function, used only with the Braccio Shield V4 and greater,
6363
* turn ON the Braccio softly and save Braccio from brokes.
6464
* The SOFT_START_CONTROL_PIN is used as a software PWM
65-
* @param soft_start_level: from -10 to +10, default value is 0 (SOFT_START_DEFAULT)
65+
* @param soft_start_level: the minimum value is -70, , default value is 0 (SOFT_START_DEFAULT)
6666
*/
6767
void _softStart(int soft_start_level);
6868

0 commit comments

Comments
 (0)