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

Commit

Permalink
Merge branch 'dev'
Browse files Browse the repository at this point in the history
  • Loading branch information
sergiotomasello committed Sep 20, 2016
2 parents d62dbb0 + 0eb245b commit 59e6f25
Show file tree
Hide file tree
Showing 3 changed files with 32 additions and 33 deletions.
2 changes: 1 addition & 1 deletion library.properties
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
name=Braccio
version=2.0
version=2.0.1
author=Andrea Martino
maintainer=Andrea <[email protected]>
sentence=For Arduino braccio only.
Expand Down
57 changes: 28 additions & 29 deletions src/Braccio.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,12 +9,12 @@
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/

#include "Braccio.h"
Expand All @@ -32,7 +32,7 @@ extern int step_elbow = 180;
extern int step_wrist_rot = 180;
extern int step_wrist_ver = 90;
extern int step_gripper = 10;


_Braccio Braccio;

Expand All @@ -43,8 +43,8 @@ _Braccio::_Braccio() {
/**
* Braccio initialization and set intial position
* Modifing this function you can set up the initial position of all the
* servo motors of Braccio
* @param soft_start_level: from -10 to +10, default value is 0 (SOFT_START_DEFAULT)
* servo motors of Braccio
* @param soft_start_level: default value is 0 (SOFT_START_DEFAULT)
* You should set begin(SOFT_START_DISABLED) if you are using the Arm Robot shield V1.6
* SOFT_START_DISABLED disable the Braccio movements
*/
Expand All @@ -62,8 +62,8 @@ unsigned int _Braccio::begin(int soft_start_level) {
wrist_rot.attach(6);
wrist_ver.attach(5);
gripper.attach(3);

//For each step motor this set up the initial degree
//For each step motor this set up the initial degree
base.write(0);
shoulder.write(40);
elbow.write(180);
Expand All @@ -78,9 +78,8 @@ unsigned int _Braccio::begin(int soft_start_level) {
step_wrist_rot = 0;
step_gripper = 73;


if(soft_start_level!=SOFT_START_DISABLED)
_softStart(soft_start_level);
_softStart(soft_start_level);
return 1;
}

Expand All @@ -93,29 +92,29 @@ void _Braccio::_softwarePWM(int high_time, int low_time){
digitalWrite(SOFT_START_CONTROL_PIN,HIGH);
delayMicroseconds(high_time);
digitalWrite(SOFT_START_CONTROL_PIN,LOW);
delayMicroseconds(low_time);
delayMicroseconds(low_time);
}

/*
* This function, used only with the Braccio Shield V4 and greater,
* turn ON the Braccio softly and save it from brokes.
* The SOFT_START_CONTROL_PIN is used as a software PWM
* @param soft_start_level: from -10 to +10, default value is 0 (SOFT_START_DEFAULT)
* @param soft_start_level: the minimum value is -70, default value is 0 (SOFT_START_DEFAULT)
*/
void _Braccio::_softStart(int soft_start_level){
void _Braccio::_softStart(int soft_start_level){
long int tmp=millis();
while(millis()-tmp < LOW_LIMIT_TIMEOUT)
_softwarePWM(30+soft_start_level, 500 - soft_start_level);
_softwarePWM(80+soft_start_level, 450 - soft_start_level); //the sum should be 530usec

while(millis()-tmp < HIGH_LIMIT_TIMEOUT)
_softwarePWM(25 + soft_start_level, 480 - soft_start_level);
_softwarePWM(75 + soft_start_level, 430 - soft_start_level); //the sum should be 505usec

digitalWrite(SOFT_START_CONTROL_PIN,HIGH);
}

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

// Check values, to avoid dangerous positions for the Braccio
if (stepDelay > 30) stepDelay = 30;
if (stepDelay > 30) stepDelay = 30;
if (stepDelay < 10) stepDelay = 10;
if (vBase < 0) vBase=0;
if (vBase > 180) vBase=180;
Expand All @@ -139,17 +138,17 @@ int _Braccio::ServoMovement(int stepDelay, int vBase, int vShoulder, int vElbow,
if (vWrist_ver > 180) vWrist_ver=180;
if (vWrist_rot > 180) vWrist_rot=180;
if (vWrist_rot < 0) vWrist_rot=0;
if (vgripper < 10) vgripper = 10;
if (vgripper < 10) vgripper = 10;
if (vgripper > 73) vgripper = 73;

int exit = 1;

//Until the all motors are in the desired position
while (exit)
{
//For each servo motor if next degree is not the same of the previuos than do the movement
if (vBase != step_base)
{
while (exit)
{
//For each servo motor if next degree is not the same of the previuos than do the movement
if (vBase != step_base)
{
base.write(step_base);
//One step ahead
if (vBase > step_base) {
Expand All @@ -161,7 +160,7 @@ int _Braccio::ServoMovement(int stepDelay, int vBase, int vShoulder, int vElbow,
}
}

if (vShoulder != step_shoulder)
if (vShoulder != step_shoulder)
{
shoulder.write(step_shoulder);
//One step ahead
Expand All @@ -175,7 +174,7 @@ int _Braccio::ServoMovement(int stepDelay, int vBase, int vShoulder, int vElbow,

}

if (vElbow != step_elbow)
if (vElbow != step_elbow)
{
elbow.write(step_elbow);
//One step ahead
Expand All @@ -189,12 +188,12 @@ int _Braccio::ServoMovement(int stepDelay, int vBase, int vShoulder, int vElbow,

}

if (vWrist_ver != step_wrist_rot)
if (vWrist_ver != step_wrist_rot)
{
wrist_rot.write(step_wrist_rot);
//One step ahead
if (vWrist_ver > step_wrist_rot) {
step_wrist_rot++;
step_wrist_rot++;
}
//One step beyond
if (vWrist_ver < step_wrist_rot) {
Expand Down Expand Up @@ -227,11 +226,11 @@ int _Braccio::ServoMovement(int stepDelay, int vBase, int vShoulder, int vElbow,
step_gripper--;
}
}

//delay between each movement
delay(stepDelay);

//It checks if all the servo motors are in the desired position
//It checks if all the servo motors are in the desired position
if ((vBase == step_base) && (vShoulder == step_shoulder)
&& (vElbow == step_elbow) && (vWrist_ver == step_wrist_rot)
&& (vWrist_rot == step_wrist_ver) && (vgripper == step_gripper)) {
Expand Down
6 changes: 3 additions & 3 deletions src/Braccio.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,8 +45,8 @@ class _Braccio {
/**
* Braccio initializations and set intial position
* Modifing this function you can set up the initial position of all the
* servo motors of the Braccio
*@param soft_start_level: from -10 to +10, default value is 0 (SOFT_START_DEFAULT)
* servo motors of Braccio
*@param soft_start_level: the minimum value is -70, default value is 0 (SOFT_START_DEFAULT)
* You should set begin(SOFT_START_DISABLED) if you are using the Arm Robot shield V1.6
*/
unsigned int begin(int soft_start_level=SOFT_START_DEFAULT);
Expand All @@ -62,7 +62,7 @@ class _Braccio {
* This function, used only with the Braccio Shield V4 and greater,
* turn ON the Braccio softly and save Braccio from brokes.
* The SOFT_START_CONTROL_PIN is used as a software PWM
* @param soft_start_level: from -10 to +10, default value is 0 (SOFT_START_DEFAULT)
* @param soft_start_level: the minimum value is -70, , default value is 0 (SOFT_START_DEFAULT)
*/
void _softStart(int soft_start_level);

Expand Down

0 comments on commit 59e6f25

Please sign in to comment.