Skip to content

Esquirio/re frame codes #90

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 4 commits into from
Sep 1, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -0,0 +1,117 @@
/**************************************************************************************
* INCLUDE
**************************************************************************************/

#include <Braccio++.h>

/**************************************************************************************
* DEFINES
**************************************************************************************/

#define BUTTON_SELECT 3
#define BUTTON_ENTER 6
#define TIME_DELAY 2000

/**************************************************************************************
* CONSTANTS
**************************************************************************************/

static float const HOME_POS[6] = {157.5, 157.5, 157.5, 157.5, 157.5, 90.0};

/**************************************************************************************
* GLOBAL VARIABLES
**************************************************************************************/

static auto gripper = Braccio.get(1);
static auto wristRoll = Braccio.get(2);
static auto wristPitch = Braccio.get(3);
static auto elbow = Braccio.get(4);
static auto shoulder = Braccio.get(5);
static auto base = Braccio.get(6);

float angles[6];

/**************************************************************************************
* SETUP/LOOP
**************************************************************************************/

void setup() {
if (Braccio.begin())
{
/* Warning: keep a safe distance from the robot and watch out for the robot's
movement. It could be speedy and hit someone. */
/* Move to home position. */
Braccio.moveTo(HOME_POS[0], HOME_POS[1], HOME_POS[2], HOME_POS[3], HOME_POS[4], HOME_POS[5]);
delay(TIME_DELAY);
}
}

void loop() {
int pressedKey = Braccio.getKey();

if (pressedKey == BUTTON_ENTER)
{
// Pinch movement
gripper.move().to(230.0f); delay(TIME_DELAY);
gripper.move().to(HOME_POS[0]); delay(TIME_DELAY);

// // Wrist Roll movement
wristRoll.move().to(0.0f); delay(TIME_DELAY);
wristRoll.move().to(HOME_POS[1]); delay(TIME_DELAY);
wristRoll.move().to(315.0f); delay(TIME_DELAY);
wristRoll.move().to(HOME_POS[1]); delay(TIME_DELAY);

// // Wrist Pitch movement
wristPitch.move().to(70.0f); delay(TIME_DELAY);
wristPitch.move().to(HOME_POS[2]); delay(TIME_DELAY);
wristPitch.move().to(260.0f); delay(TIME_DELAY);
wristPitch.move().to(HOME_POS[2]); delay(TIME_DELAY);

// Elbow movement
for(float i=HOME_POS[3]; i >= 70.0; i-=5)
{ elbow.move().to(i); delay(TIME_DELAY/2000); }
elbow.move().to(HOME_POS[3]); delay(TIME_DELAY);
for(float i=HOME_POS[3]; i <= 260.0; i+=5)
{ elbow.move().to(i); delay(TIME_DELAY/2000); }
elbow.move().to(HOME_POS[3]); delay(TIME_DELAY);

// Shoulder movement
shoulder.move().to(120.0f); delay(TIME_DELAY/2);
shoulder.move().to(90.0f); delay(TIME_DELAY/2);
shoulder.move().to(120.0f); delay(TIME_DELAY/2);
shoulder.move().to(HOME_POS[4]); delay(TIME_DELAY);
shoulder.move().to(200.0f); delay(TIME_DELAY/2);
shoulder.move().to(230.0f); delay(TIME_DELAY/2);
shoulder.move().to(200.0f); delay(TIME_DELAY/2);
shoulder.move().to(HOME_POS[4]); delay(TIME_DELAY);

// Base movement
base.move().to(0.0f); delay(TIME_DELAY);
base.move().to(HOME_POS[5]); delay(TIME_DELAY);
base.move().to(315.0f); delay(TIME_DELAY);
base.move().to(HOME_POS[5]); delay(TIME_DELAY);

while(pressedKey == BUTTON_ENTER) { pressedKey = Braccio.getKey(); }
}

if (pressedKey == BUTTON_SELECT)
{
// Fetch the joints positions
Braccio.positions(angles);

// Print the joint angles
Serial.println("************* Joints Angles *************");
Serial.println("|\tMotor ID\t|\tAngle\t|");
Serial.println("----------------------------------------");
Serial.print("| 1 - Gripper\t\t|\t" + String(angles[0]) + "\t|\n" +
"| 2 - Wrist Rotation\t|\t" + String(angles[1]) + "\t|\n" +
"| 3 - Wrist Vertical\t|\t" + String(angles[2]) + "\t|\n" +
"| 4 - Elbow\t\t|\t" + String(angles[3]) + "\t|\n" +
"| 5 - Shoulder\t\t|\t" + String(angles[4]) + "\t|\n" +
"| 6 - Base\t\t|\t" + String(angles[5]) + "\t|\n" +
"*****************************************\n\n\n\n\n");

while(pressedKey == BUTTON_SELECT) { pressedKey = Braccio.getKey(); }

}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,81 @@
#include <Braccio++.h>

#define MARGIN_LEFT 0
#define MARGIN_TOP 0

// Arduino Colors
#define COLOR_TEAL 0x00878F
#define COLOR_LIGHT_TEAL 0x62AEB2
#define COLOR_ORANGE 0xE47128
#define COLOR_YELLOW 0xE5AD24
#define COLOR_WHITE 0xFFFFFF

static const char * btnm_map[] = {"Option 1", "Option 2", "\n",
"Option 3", "Option 4", "\n",
"Option 5", "Option 6", "\0"
};

void setup() {
if (!Braccio.begin(customMenu)) {
if (Serial) Serial.println("Braccio.begin() failed.");
for(;;) { }
}
}

void loop() {
// Let here empty.
}

void customMenu(){
Braccio.lvgl_lock();

static lv_style_t style_bg;
lv_style_init(&style_bg);
lv_style_set_bg_color(&style_bg, lv_color_hex(COLOR_WHITE));

static lv_style_t style_btn;
lv_style_init(&style_btn);
lv_style_set_bg_color(&style_btn, lv_color_hex(COLOR_YELLOW));
lv_style_set_border_color(&style_btn, lv_color_hex(COLOR_LIGHT_TEAL));
lv_style_set_border_width(&style_btn, 2);
lv_style_set_text_color(&style_btn, lv_color_hex(COLOR_TEAL));


lv_obj_t * btnm = lv_btnmatrix_create(lv_scr_act());
lv_btnmatrix_set_map(btnm, btnm_map);
lv_obj_align(btnm, LV_ALIGN_CENTER, MARGIN_LEFT, MARGIN_TOP);

lv_obj_add_style(btnm, &style_bg, 0);
lv_obj_add_style(btnm, &style_btn, LV_PART_ITEMS);

lv_btnmatrix_set_btn_ctrl(btnm, 0, LV_BTNMATRIX_CTRL_CHECKABLE);
lv_btnmatrix_set_btn_ctrl(btnm, 1, LV_BTNMATRIX_CTRL_CHECKABLE);
lv_btnmatrix_set_btn_ctrl(btnm, 2, LV_BTNMATRIX_CTRL_CHECKABLE);
lv_btnmatrix_set_btn_ctrl(btnm, 3, LV_BTNMATRIX_CTRL_CHECKABLE);
lv_btnmatrix_set_btn_ctrl(btnm, 4, LV_BTNMATRIX_CTRL_CHECKABLE);
lv_btnmatrix_set_btn_ctrl(btnm, 5, LV_BTNMATRIX_CTRL_CHECKABLE);

lv_btnmatrix_set_one_checked(btnm, true);

lv_obj_add_event_cb(btnm, eventHandler, LV_EVENT_ALL, NULL);

Braccio.lvgl_unlock();

Braccio.connectJoystickTo(btnm);
}

static void eventHandler(lv_event_t * e){
Braccio.lvgl_lock();

lv_event_code_t code = lv_event_get_code(e);
lv_obj_t * obj = lv_event_get_target(e);
if (code == LV_EVENT_CLICKED) {
uint32_t id = lv_btnmatrix_get_selected_btn(obj);
const char * txt = lv_btnmatrix_get_btn_text(obj, id);

LV_LOG_USER("%s was selected\n", txt);
Serial.println(String(txt) + " was selected.");
}

Braccio.lvgl_unlock();
}
Original file line number Diff line number Diff line change
@@ -1,6 +1,19 @@
/**************************************************************************************
* INCLUDE
**************************************************************************************/

#include <Braccio++.h>

// Variables
/**************************************************************************************
* DEFINES
**************************************************************************************/

#define TIME_DELAY 1000

/**************************************************************************************
* GLOBAL VARIABLES
**************************************************************************************/

// Braccio ++ joints
auto gripper = Braccio.get(1);
auto wristRoll = Braccio.get(2);
Expand All @@ -9,28 +22,28 @@ auto elbow = Braccio.get(4);
auto shoulder = Braccio.get(5);
auto base = Braccio.get(6);

float initialGripper = 160.0;
float initialBase = 90.0;
float initialAngle = 150.0;
float initialAngle = 157.5;

float angles[6];

/**************************************************************************************
* SETUP/LOOP
**************************************************************************************/

void setup() {
Braccio.begin();
delay(500); // Waits for the Braccio initialization

// Send motors initial angle
gripper.move().to(initialGripper);
delay(100);
wristRoll.move().to(initialAngle);
delay(100);
wristPitch.move().to(initialAngle);
delay(100);
elbow.move().to(initialAngle);
delay(100);
shoulder.move().to(initialAngle);
delay(100);
base.move().to(initialBase);
delay(100);
if (Braccio.begin()){
/* Warning: keep a safe distance from the robot and watch out for the robot's
movement. It could be speedy and hit someone. */

/* Move to home position. */
gripper.move().to(initialAngle); delay(TIME_DELAY);
wristRoll.move().to(initialAngle); delay(TIME_DELAY);
wristPitch.move().to(initialAngle); delay(TIME_DELAY);
elbow.move().to(initialAngle); delay(TIME_DELAY);
shoulder.move().to(initialAngle); delay(TIME_DELAY);
base.move().to(initialBase); delay(TIME_DELAY);
}

Serial.begin(115200);
while(!Serial){}
Expand All @@ -53,5 +66,5 @@ void loop() {
Serial.println("*****************************************\n\n\n\n\n");
Serial.println("\n\n\n\n");

delay(1000);
delay(TIME_DELAY);
}
Original file line number Diff line number Diff line change
@@ -1,7 +1,27 @@
/**************************************************************************************
* INCLUDE
**************************************************************************************/

#include <Braccio++.h>

/**************************************************************************************
* DEFINES
**************************************************************************************/

#define BUTTON_ENTER 6
#define TIME_DELAY 1000

/**************************************************************************************
* CONSTANTS
**************************************************************************************/

float const HOME_POS[6] = {157.5, 157.5, 157.5, 157.5, 157.5, 90.0};
float const WAVE_POS[6] = {180.0, 260.0, 157.5, 157.5, 157.5, 180.0};

/**************************************************************************************
* GLOBAL VARIABLES
**************************************************************************************/

// Braccio ++ joints
auto gripper = Braccio.get(1);
auto wristRoll = Braccio.get(2);
Expand All @@ -10,41 +30,41 @@ auto elbow = Braccio.get(4);
auto shoulder = Braccio.get(5);
auto base = Braccio.get(6);

/* Variables */
// initialAngles[6] = {gripper, wristRoll, wristPitch, elbow, shoulder, base}
float homePos[6] = {160.0, 150.0, 220.0, 220.0, 100.0, 180.0};
float wavePos[6] = {180.0, 250.0, 145.0, 150.0, 150.0, 90.0};

bool movement = false; // Flag to initialize joints' movements

/**************************************************************************************
* SETUP/LOOP
**************************************************************************************/

void setup() {
Braccio.begin();
delay(500); // Waits for the Braccio initialization
if (Braccio.begin()){
/* Warning:
Keep a safe distance from the robot until you make sure the code is properly
working. Be mindful of the robot’s movement prior to that, as it could be
speedy and accidentally hit someone.
*/

// Set motors initial angle
// Should move all the motors at once
Braccio.moveTo(homePos[0], homePos[1], homePos[2], homePos[3], homePos[4], homePos[5]);
delay(500);
/* Move to home position. */
Braccio.moveTo(HOME_POS[0], HOME_POS[1], HOME_POS[2], HOME_POS[3], HOME_POS[4], HOME_POS[5]);
delay(TIME_DELAY);
}
}

// Waving whit Wrist pitch
// Waving with Wrist pitch
void loop() {
int pressedKey = Braccio.getKey();

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

if (movement) {
Braccio.moveTo(wavePos[0], wavePos[1], wavePos[2], wavePos[3], wavePos[4], wavePos[5]);
delay(1000);

for (int i = 1; i <= 10; i++) {
wristPitch.move().to(100.0f);
delay(300);
wristPitch.move().to(190.0f);
delay(600);
wristPitch.move().to(145.0f);
delay(300);
Braccio.moveTo(WAVE_POS[0], WAVE_POS[1], WAVE_POS[2], WAVE_POS[3], WAVE_POS[4], WAVE_POS[5]);
delay(TIME_DELAY);

for (int i = 1; i <= 5; i++) {
wristPitch.move().to(120.0f); delay(TIME_DELAY);
wristPitch.move().to(200.0f); delay(2*TIME_DELAY);
wristPitch.move().to(WAVE_POS[3]);
}

movement = false; // Stop joints' movements
Expand Down
Loading