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 (" |\t Motor ID\t |\t Angle\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
+ }
0 commit comments