Skip to content

Commit b4d1b75

Browse files
authored
Merge pull request #90 from arduino-libraries/Esquirio/re_frame_codes
Esquirio/re frame codes
2 parents 26e270f + aaa8653 commit b4d1b75

File tree

25 files changed

+310
-61
lines changed

25 files changed

+310
-61
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,117 @@
1+
/**************************************************************************************
2+
* INCLUDE
3+
**************************************************************************************/
4+
5+
#include <Braccio++.h>
6+
7+
/**************************************************************************************
8+
* DEFINES
9+
**************************************************************************************/
10+
11+
#define BUTTON_SELECT 3
12+
#define BUTTON_ENTER 6
13+
#define TIME_DELAY 2000
14+
15+
/**************************************************************************************
16+
* CONSTANTS
17+
**************************************************************************************/
18+
19+
static float const HOME_POS[6] = {157.5, 157.5, 157.5, 157.5, 157.5, 90.0};
20+
21+
/**************************************************************************************
22+
* GLOBAL VARIABLES
23+
**************************************************************************************/
24+
25+
static auto gripper = Braccio.get(1);
26+
static auto wristRoll = Braccio.get(2);
27+
static auto wristPitch = Braccio.get(3);
28+
static auto elbow = Braccio.get(4);
29+
static auto shoulder = Braccio.get(5);
30+
static auto base = Braccio.get(6);
31+
32+
float angles[6];
33+
34+
/**************************************************************************************
35+
* SETUP/LOOP
36+
**************************************************************************************/
37+
38+
void setup() {
39+
if (Braccio.begin())
40+
{
41+
/* Warning: keep a safe distance from the robot and watch out for the robot's
42+
movement. It could be speedy and hit someone. */
43+
/* Move to home position. */
44+
Braccio.moveTo(HOME_POS[0], HOME_POS[1], HOME_POS[2], HOME_POS[3], HOME_POS[4], HOME_POS[5]);
45+
delay(TIME_DELAY);
46+
}
47+
}
48+
49+
void loop() {
50+
int pressedKey = Braccio.getKey();
51+
52+
if (pressedKey == BUTTON_ENTER)
53+
{
54+
// Pinch movement
55+
gripper.move().to(230.0f); delay(TIME_DELAY);
56+
gripper.move().to(HOME_POS[0]); delay(TIME_DELAY);
57+
58+
// // Wrist Roll movement
59+
wristRoll.move().to(0.0f); delay(TIME_DELAY);
60+
wristRoll.move().to(HOME_POS[1]); delay(TIME_DELAY);
61+
wristRoll.move().to(315.0f); delay(TIME_DELAY);
62+
wristRoll.move().to(HOME_POS[1]); delay(TIME_DELAY);
63+
64+
// // Wrist Pitch movement
65+
wristPitch.move().to(70.0f); delay(TIME_DELAY);
66+
wristPitch.move().to(HOME_POS[2]); delay(TIME_DELAY);
67+
wristPitch.move().to(260.0f); delay(TIME_DELAY);
68+
wristPitch.move().to(HOME_POS[2]); delay(TIME_DELAY);
69+
70+
// Elbow movement
71+
for(float i=HOME_POS[3]; i >= 70.0; i-=5)
72+
{ elbow.move().to(i); delay(TIME_DELAY/2000); }
73+
elbow.move().to(HOME_POS[3]); delay(TIME_DELAY);
74+
for(float i=HOME_POS[3]; i <= 260.0; i+=5)
75+
{ elbow.move().to(i); delay(TIME_DELAY/2000); }
76+
elbow.move().to(HOME_POS[3]); delay(TIME_DELAY);
77+
78+
// Shoulder movement
79+
shoulder.move().to(120.0f); delay(TIME_DELAY/2);
80+
shoulder.move().to(90.0f); delay(TIME_DELAY/2);
81+
shoulder.move().to(120.0f); delay(TIME_DELAY/2);
82+
shoulder.move().to(HOME_POS[4]); delay(TIME_DELAY);
83+
shoulder.move().to(200.0f); delay(TIME_DELAY/2);
84+
shoulder.move().to(230.0f); delay(TIME_DELAY/2);
85+
shoulder.move().to(200.0f); delay(TIME_DELAY/2);
86+
shoulder.move().to(HOME_POS[4]); delay(TIME_DELAY);
87+
88+
// Base movement
89+
base.move().to(0.0f); delay(TIME_DELAY);
90+
base.move().to(HOME_POS[5]); delay(TIME_DELAY);
91+
base.move().to(315.0f); delay(TIME_DELAY);
92+
base.move().to(HOME_POS[5]); delay(TIME_DELAY);
93+
94+
while(pressedKey == BUTTON_ENTER) { pressedKey = Braccio.getKey(); }
95+
}
96+
97+
if (pressedKey == BUTTON_SELECT)
98+
{
99+
// Fetch the joints positions
100+
Braccio.positions(angles);
101+
102+
// Print the joint angles
103+
Serial.println("************* Joints Angles *************");
104+
Serial.println("|\tMotor ID\t|\tAngle\t|");
105+
Serial.println("----------------------------------------");
106+
Serial.print("| 1 - Gripper\t\t|\t" + String(angles[0]) + "\t|\n" +
107+
"| 2 - Wrist Rotation\t|\t" + String(angles[1]) + "\t|\n" +
108+
"| 3 - Wrist Vertical\t|\t" + String(angles[2]) + "\t|\n" +
109+
"| 4 - Elbow\t\t|\t" + String(angles[3]) + "\t|\n" +
110+
"| 5 - Shoulder\t\t|\t" + String(angles[4]) + "\t|\n" +
111+
"| 6 - Base\t\t|\t" + String(angles[5]) + "\t|\n" +
112+
"*****************************************\n\n\n\n\n");
113+
114+
while(pressedKey == BUTTON_SELECT) { pressedKey = Braccio.getKey(); }
115+
116+
}
117+
}
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,81 @@
1+
#include <Braccio++.h>
2+
3+
#define MARGIN_LEFT 0
4+
#define MARGIN_TOP 0
5+
6+
// Arduino Colors
7+
#define COLOR_TEAL 0x00878F
8+
#define COLOR_LIGHT_TEAL 0x62AEB2
9+
#define COLOR_ORANGE 0xE47128
10+
#define COLOR_YELLOW 0xE5AD24
11+
#define COLOR_WHITE 0xFFFFFF
12+
13+
static const char * btnm_map[] = {"Option 1", "Option 2", "\n",
14+
"Option 3", "Option 4", "\n",
15+
"Option 5", "Option 6", "\0"
16+
};
17+
18+
void setup() {
19+
if (!Braccio.begin(customMenu)) {
20+
if (Serial) Serial.println("Braccio.begin() failed.");
21+
for(;;) { }
22+
}
23+
}
24+
25+
void loop() {
26+
// Let here empty.
27+
}
28+
29+
void customMenu(){
30+
Braccio.lvgl_lock();
31+
32+
static lv_style_t style_bg;
33+
lv_style_init(&style_bg);
34+
lv_style_set_bg_color(&style_bg, lv_color_hex(COLOR_WHITE));
35+
36+
static lv_style_t style_btn;
37+
lv_style_init(&style_btn);
38+
lv_style_set_bg_color(&style_btn, lv_color_hex(COLOR_YELLOW));
39+
lv_style_set_border_color(&style_btn, lv_color_hex(COLOR_LIGHT_TEAL));
40+
lv_style_set_border_width(&style_btn, 2);
41+
lv_style_set_text_color(&style_btn, lv_color_hex(COLOR_TEAL));
42+
43+
44+
lv_obj_t * btnm = lv_btnmatrix_create(lv_scr_act());
45+
lv_btnmatrix_set_map(btnm, btnm_map);
46+
lv_obj_align(btnm, LV_ALIGN_CENTER, MARGIN_LEFT, MARGIN_TOP);
47+
48+
lv_obj_add_style(btnm, &style_bg, 0);
49+
lv_obj_add_style(btnm, &style_btn, LV_PART_ITEMS);
50+
51+
lv_btnmatrix_set_btn_ctrl(btnm, 0, LV_BTNMATRIX_CTRL_CHECKABLE);
52+
lv_btnmatrix_set_btn_ctrl(btnm, 1, LV_BTNMATRIX_CTRL_CHECKABLE);
53+
lv_btnmatrix_set_btn_ctrl(btnm, 2, LV_BTNMATRIX_CTRL_CHECKABLE);
54+
lv_btnmatrix_set_btn_ctrl(btnm, 3, LV_BTNMATRIX_CTRL_CHECKABLE);
55+
lv_btnmatrix_set_btn_ctrl(btnm, 4, LV_BTNMATRIX_CTRL_CHECKABLE);
56+
lv_btnmatrix_set_btn_ctrl(btnm, 5, LV_BTNMATRIX_CTRL_CHECKABLE);
57+
58+
lv_btnmatrix_set_one_checked(btnm, true);
59+
60+
lv_obj_add_event_cb(btnm, eventHandler, LV_EVENT_ALL, NULL);
61+
62+
Braccio.lvgl_unlock();
63+
64+
Braccio.connectJoystickTo(btnm);
65+
}
66+
67+
static void eventHandler(lv_event_t * e){
68+
Braccio.lvgl_lock();
69+
70+
lv_event_code_t code = lv_event_get_code(e);
71+
lv_obj_t * obj = lv_event_get_target(e);
72+
if (code == LV_EVENT_CLICKED) {
73+
uint32_t id = lv_btnmatrix_get_selected_btn(obj);
74+
const char * txt = lv_btnmatrix_get_btn_text(obj, id);
75+
76+
LV_LOG_USER("%s was selected\n", txt);
77+
Serial.println(String(txt) + " was selected.");
78+
}
79+
80+
Braccio.lvgl_unlock();
81+
}
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,19 @@
1+
/**************************************************************************************
2+
* INCLUDE
3+
**************************************************************************************/
4+
15
#include <Braccio++.h>
26

3-
// Variables
7+
/**************************************************************************************
8+
* DEFINES
9+
**************************************************************************************/
10+
11+
#define TIME_DELAY 1000
12+
13+
/**************************************************************************************
14+
* GLOBAL VARIABLES
15+
**************************************************************************************/
16+
417
// Braccio ++ joints
518
auto gripper = Braccio.get(1);
619
auto wristRoll = Braccio.get(2);
@@ -9,28 +22,28 @@ auto elbow = Braccio.get(4);
922
auto shoulder = Braccio.get(5);
1023
auto base = Braccio.get(6);
1124

12-
float initialGripper = 160.0;
1325
float initialBase = 90.0;
14-
float initialAngle = 150.0;
26+
float initialAngle = 157.5;
27+
1528
float angles[6];
1629

30+
/**************************************************************************************
31+
* SETUP/LOOP
32+
**************************************************************************************/
33+
1734
void setup() {
18-
Braccio.begin();
19-
delay(500); // Waits for the Braccio initialization
20-
21-
// Send motors initial angle
22-
gripper.move().to(initialGripper);
23-
delay(100);
24-
wristRoll.move().to(initialAngle);
25-
delay(100);
26-
wristPitch.move().to(initialAngle);
27-
delay(100);
28-
elbow.move().to(initialAngle);
29-
delay(100);
30-
shoulder.move().to(initialAngle);
31-
delay(100);
32-
base.move().to(initialBase);
33-
delay(100);
35+
if (Braccio.begin()){
36+
/* Warning: keep a safe distance from the robot and watch out for the robot's
37+
movement. It could be speedy and hit someone. */
38+
39+
/* Move to home position. */
40+
gripper.move().to(initialAngle); delay(TIME_DELAY);
41+
wristRoll.move().to(initialAngle); delay(TIME_DELAY);
42+
wristPitch.move().to(initialAngle); delay(TIME_DELAY);
43+
elbow.move().to(initialAngle); delay(TIME_DELAY);
44+
shoulder.move().to(initialAngle); delay(TIME_DELAY);
45+
base.move().to(initialBase); delay(TIME_DELAY);
46+
}
3447

3548
Serial.begin(115200);
3649
while(!Serial){}
@@ -53,5 +66,5 @@ void loop() {
5366
Serial.println("*****************************************\n\n\n\n\n");
5467
Serial.println("\n\n\n\n");
5568

56-
delay(1000);
69+
delay(TIME_DELAY);
5770
}

examples/Platform_Tutorials/projects/p01-moving-braccio/02_waving_with_Braccio/02_waving_with_Braccio.ino

+42-22
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,27 @@
1+
/**************************************************************************************
2+
* INCLUDE
3+
**************************************************************************************/
4+
15
#include <Braccio++.h>
26

7+
/**************************************************************************************
8+
* DEFINES
9+
**************************************************************************************/
10+
311
#define BUTTON_ENTER 6
12+
#define TIME_DELAY 1000
13+
14+
/**************************************************************************************
15+
* CONSTANTS
16+
**************************************************************************************/
17+
18+
float const HOME_POS[6] = {157.5, 157.5, 157.5, 157.5, 157.5, 90.0};
19+
float const WAVE_POS[6] = {180.0, 260.0, 157.5, 157.5, 157.5, 180.0};
420

21+
/**************************************************************************************
22+
* GLOBAL VARIABLES
23+
**************************************************************************************/
24+
525
// Braccio ++ joints
626
auto gripper = Braccio.get(1);
727
auto wristRoll = Braccio.get(2);
@@ -10,41 +30,41 @@ auto elbow = Braccio.get(4);
1030
auto shoulder = Braccio.get(5);
1131
auto base = Braccio.get(6);
1232

13-
/* Variables */
14-
// initialAngles[6] = {gripper, wristRoll, wristPitch, elbow, shoulder, base}
15-
float homePos[6] = {160.0, 150.0, 220.0, 220.0, 100.0, 180.0};
16-
float wavePos[6] = {180.0, 250.0, 145.0, 150.0, 150.0, 90.0};
17-
1833
bool movement = false; // Flag to initialize joints' movements
1934

35+
/**************************************************************************************
36+
* SETUP/LOOP
37+
**************************************************************************************/
38+
2039
void setup() {
21-
Braccio.begin();
22-
delay(500); // Waits for the Braccio initialization
40+
if (Braccio.begin()){
41+
/* Warning:
42+
Keep a safe distance from the robot until you make sure the code is properly
43+
working. Be mindful of the robot’s movement prior to that, as it could be
44+
speedy and accidentally hit someone.
45+
*/
2346

24-
// Set motors initial angle
25-
// Should move all the motors at once
26-
Braccio.moveTo(homePos[0], homePos[1], homePos[2], homePos[3], homePos[4], homePos[5]);
27-
delay(500);
47+
/* Move to home position. */
48+
Braccio.moveTo(HOME_POS[0], HOME_POS[1], HOME_POS[2], HOME_POS[3], HOME_POS[4], HOME_POS[5]);
49+
delay(TIME_DELAY);
50+
}
2851
}
2952

30-
// Waving whit Wrist pitch
53+
// Waving with Wrist pitch
3154
void loop() {
3255
int pressedKey = Braccio.getKey();
3356

3457
if (pressedKey == BUTTON_ENTER)
3558
movement = true; // Trigger joints' movements
3659

3760
if (movement) {
38-
Braccio.moveTo(wavePos[0], wavePos[1], wavePos[2], wavePos[3], wavePos[4], wavePos[5]);
39-
delay(1000);
40-
41-
for (int i = 1; i <= 10; i++) {
42-
wristPitch.move().to(100.0f);
43-
delay(300);
44-
wristPitch.move().to(190.0f);
45-
delay(600);
46-
wristPitch.move().to(145.0f);
47-
delay(300);
61+
Braccio.moveTo(WAVE_POS[0], WAVE_POS[1], WAVE_POS[2], WAVE_POS[3], WAVE_POS[4], WAVE_POS[5]);
62+
delay(TIME_DELAY);
63+
64+
for (int i = 1; i <= 5; i++) {
65+
wristPitch.move().to(120.0f); delay(TIME_DELAY);
66+
wristPitch.move().to(200.0f); delay(2*TIME_DELAY);
67+
wristPitch.move().to(WAVE_POS[3]);
4868
}
4969

5070
movement = false; // Stop joints' movements

0 commit comments

Comments
 (0)