Skip to content
This repository was archived by the owner on Sep 4, 2025. It is now read-only.

Commit f21b4b3

Browse files
authored
Merge pull request makerforgetech#84 from makerforgetech/feature/arduino_upgrades
Feature/arduino upgrades
2 parents 55f1011 + ee93324 commit f21b4b3

File tree

5 files changed

+67
-32
lines changed

5 files changed

+67
-32
lines changed

animations/look_down.json

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
[
22
{"servo:pan:mvabs": 50},
33
{"sleep": 0.5},
4-
{"servo:tilt:mvabs": 20},
4+
{"servo:tilt:mvabs": 80},
55
{"sleep": 1}
66
]

animations/look_up.json

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
[
22
{"servo:pan:mvabs": 50},
33
{"sleep": 0.5},
4-
{"servo:tilt:mvabs": 80},
4+
{"servo:tilt:mvabs": 20},
55
{"sleep": 1}
66
]

arduino_sketch/Config.h

Lines changed: 16 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -37,50 +37,55 @@
3737
#define SERVO_SPEED_MIN 20
3838
#define SERVO_SPEED_MAX 80
3939

40-
//#define DEBUG
40+
// #define DEBUG
4141

4242
#define SERVO_COUNT 8 // Number of servos to be controlled by ServoEasing
4343

4444
#define LEG_IK_MIN 75 // Min solvable height of leg between hip and ankle
45-
#define LEG_IK_MAX 170 // Max solvable height of leg between hip and ankle
45+
#define LEG_IK_MAX 180 // Max solvable height of leg between hip and ankle
4646

4747
#define NOVAL 1000
4848

49-
//#define MPU6050_ENABLED // Enable MPU6050
49+
#define MPU6050_ENABLED // Enable MPU6050
5050
//#define MPU6050_DEBUG // Debug in serial plotter
51-
//#define ANIMATE_ENABLED // Enable random animations
52-
51+
#define ANIMATE_ENABLED // Enable random animations
5352

5453
// Arrays to store servo min / max positions to avoid mechanical issues due
5554
// NOTE: attach() disregards this, set PosRest to be within range of the servo's physical boundaries
56-
int PosMin[SERVO_COUNT] = {0, 0, 5, 0, 0, 10, 60, 30};
55+
int PosMin[SERVO_COUNT] = {0, 0, 5, 0, 0, 20, 60, 30};
5756
int PosMax[SERVO_COUNT] = {180, 180, 165, 180, 180, 180, 120, 150};
5857
int PosSleep[SERVO_COUNT] = {40, 60, 95, 140, 120, 85, PosMax[7], 90};
5958
//int PrepRestFromSleep[SERVO_COUNT] = {80, PosMin[1], PosMax[2], 100, PosMax[4], PosMin[5], S7_REST, 80, S9_REST};
6059
//int PrepSleepFromRest[SERVO_COUNT] = {S1_REST, S2_REST, S3_REST, S4_REST, S5_REST, S6_REST, S7_REST, 80, S9_REST};
6160

6261
// Starting positions
6362
//0, 3 = HIP
64-
int PosStart[SERVO_COUNT] = {60, 0, 165, 120, 180, 10, 90, 90};
65-
63+
int PosStart[SERVO_COUNT] = {60, 0, 165, 120, 180, 20, 90, 90};
6664

65+
int PosBackpack[SERVO_COUNT] = {45, 90, 165, 135, 90, 20, 90, 90}; // straighten legs and point feet to fit in backpack upright
6766

6867
//int PosRest[SERVO_COUNT] = {S1_REST, S2_REST, S3_REST, S4_REST, S5_REST, S6_REST, S7_REST, S8_REST, S9_REST};
69-
int PosRest[SERVO_COUNT] = {60, 0, 165, 120, 180, 10, 90, 90};
68+
int PosRest[SERVO_COUNT] = {60, 0, 165, 120, 180, 20, 90, 90};
7069

7170
int PosConfig[SERVO_COUNT] = {90, 90, 90, 90, 90, 90, 90, 90};
7271

7372
// Poses
74-
int PosStand[SERVO_COUNT] = {40, 60, 95, 140, 120, 85, NOVAL, NOVAL};
73+
int PosStand[SERVO_COUNT] = {45, 75, 80, 135, 105, 100, NOVAL, NOVAL};
7574
int PosLookLeft[SERVO_COUNT] = {NOVAL, NOVAL, NOVAL, NOVAL, NOVAL, NOVAL, NOVAL, 180};
7675
int PosLookRight[SERVO_COUNT] = {NOVAL, NOVAL, NOVAL, NOVAL, NOVAL, NOVAL, NOVAL, 0};
77-
int PosLookRandom[SERVO_COUNT] = {NOVAL, NOVAL, NOVAL, NOVAL, NOVAL, NOVAL, -1, NOVAL}; // Made random by calling the function moveRandom() if the value is -1
76+
int PosLookRandom[SERVO_COUNT] = {NOVAL, NOVAL, NOVAL, NOVAL, NOVAL, NOVAL, -1, -1}; // Made random by calling the function moveRandom() if the value is -1
7877
int PosLookUp[SERVO_COUNT] = {NOVAL, NOVAL, NOVAL, NOVAL, NOVAL, NOVAL, 60, 90};
7978
int PosLookDown[SERVO_COUNT] = {NOVAL, NOVAL, NOVAL, NOVAL, NOVAL, NOVAL, 120, 90};
8079

8180
// Array of poses except PosRest and PosSleep (which are used for initialization and reset of position)
8281
int *Poses[] = {PosStand, PosLookLeft, PosLookRight, PosLookUp, PosLookDown, PosLookRandom};
8382

83+
int backpackPin = 12;
84+
bool backpack = false;
85+
86+
int restrainPin = PIN_A1;
87+
bool restrainingBolt = false;
88+
8489
void blinkLED()
8590
{
8691
digitalWrite(LED_BUILTIN, HIGH);

arduino_sketch/ServoManager.h

Lines changed: 22 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -26,12 +26,23 @@ class ServoManager
2626
void doInit()
2727
{
2828
// IMPORTANT: Communication from Pi uses index, these must be attached in the same order as they are referenced in the pi config
29-
ServoLLH.attach(PIN_SLLH, PosStart[0]);
30-
ServoLLK.attach(PIN_SLLK, PosStart[1]);
31-
ServoLLA.attach(PIN_SLLA, PosStart[2]);
32-
ServoRLH.attach(PIN_SRLH, PosStart[3]);
33-
ServoRLK.attach(PIN_SRLK, PosStart[4]);
34-
ServoRLA.attach(PIN_SRLA, PosStart[5]);
29+
if (backpack == true)
30+
{
31+
ServoLLH.attach(PIN_SLLH, PosBackpack[0]);
32+
ServoLLK.attach(PIN_SLLK, PosBackpack[1]);
33+
ServoLLA.attach(PIN_SLLA, PosBackpack[2]);
34+
ServoRLH.attach(PIN_SRLH, PosBackpack[3]);
35+
ServoRLK.attach(PIN_SRLK, PosBackpack[4]);
36+
ServoRLA.attach(PIN_SRLA, PosBackpack[5]);
37+
}
38+
else {
39+
ServoLLH.attach(PIN_SLLH, PosStart[0]);
40+
ServoLLK.attach(PIN_SLLK, PosStart[1]);
41+
ServoLLA.attach(PIN_SLLA, PosStart[2]);
42+
ServoRLH.attach(PIN_SRLH, PosStart[3]);
43+
ServoRLK.attach(PIN_SRLK, PosStart[4]);
44+
ServoRLA.attach(PIN_SRLA, PosStart[5]);
45+
}
3546
ServoNT.attach(PIN_SNT, PosStart[6]);
3647
ServoNP.attach(PIN_SNP, PosStart[7]);
3748

@@ -118,20 +129,18 @@ class ServoManager
118129

119130
void moveSingleServo(uint8_t pServoIndex, int pPos, boolean isRelative)
120131
{
121-
if (isRelative)
132+
if ((backpack == true || restrainingBolt == true) && pServoIndex < 6)
133+
{
134+
// Serial.println("Backpack or restrained mode, skipping leg servos");
135+
}
136+
else if (isRelative)
122137
{
123-
// Serial.print(" Moving from: ");
124-
// Serial.print(ServoEasing::ServoEasingNextPositionArray[pServoIndex]);
125-
// Serial.print(" to: ");
126-
// Serial.println(ServoEasing::ServoEasingNextPositionArray[pServoIndex] + pPos);
127138
ServoEasing::ServoEasingNextPositionArray[pServoIndex] = ServoEasing::ServoEasingNextPositionArray[pServoIndex] + pPos;
128139
}
129140
else
130141
{
131142
ServoEasing::ServoEasingNextPositionArray[pServoIndex] = pPos;
132143
}
133-
// setEaseToForAllServosSynchronizeAndStartInterrupt(tSpeed);
134-
135144
// Return actual value to Pi
136145
PiConnect::write_i16(ServoEasing::ServoEasingNextPositionArray[pServoIndex]);
137146
}

arduino_sketch/arduino_sketch.ino

Lines changed: 27 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,8 @@ boolean calibrateRest = false;
3333

3434
bool shouldMove = false;
3535

36+
bool piControl = false;
37+
3638
void setup()
3739
{
3840
// Init LED pin
@@ -43,6 +45,22 @@ void setup()
4345
bootTime = millis();
4446
// Init serial
4547
Serial.begin(115200);
48+
49+
50+
pinMode(backpackPin, INPUT_PULLUP); // sets the digital pin as input
51+
if (digitalRead(backpackPin) == LOW) // Check once on startup
52+
{
53+
Serial.println("Backpack detected");
54+
backpack = true;
55+
}
56+
57+
pinMode(restrainPin, INPUT_PULLUP); // sets the digital pin as input
58+
if (digitalRead(restrainPin) == LOW) // Check once on startup
59+
{
60+
Serial.println("Restraint detected");
61+
restrainingBolt = true;
62+
}
63+
4664
// Init ServoManager
4765
servoManager.doInit();
4866
servoManager.setSpeed(SERVO_SPEED_MIN);
@@ -57,7 +75,7 @@ void setup()
5775
// allTo90();
5876

5977
// Move to rest position + calculate IK and store as rest position
60-
//doRest();
78+
// doRest();
6179

6280
// Custom log message (enable DEBUG in Config.h to see this)
6381
cLog("Start loop");
@@ -83,7 +101,7 @@ void allTo90()
83101
void doRest()
84102
{
85103
cLog("Resting");
86-
isResting = true;
104+
87105
// Reset to slow speed
88106
servoManager.setSpeed(SERVO_SPEED_MIN);
89107
if (calibrateRest == false)
@@ -141,6 +159,7 @@ void hipAdjust()
141159
tilt.read();
142160
//Serial.println(tilt.getPitch());
143161
servoManager.hipAdjust(tilt.getPitch());
162+
setEaseToForAllServosSynchronizeAndStartInterrupt(servoManager.getSpeed());
144163
}
145164
#endif
146165

@@ -163,6 +182,7 @@ void loop()
163182
bool receiving = getOrdersFromPi();
164183
while(receiving)
165184
{
185+
piControl = true;
166186
delay(50); // Wait a short time for any other orders
167187
receiving = getOrdersFromPi();
168188
shouldMove = !receiving; // Only move when there are no other orders
@@ -179,17 +199,17 @@ void loop()
179199
// Orders from pi will set sleep time so that the animation does not take precedence
180200
if (!isSleeping())
181201
{
182-
if (isResting)
202+
if (isResting && piControl == false) // Only do this if the Pi is not in control (i.e. switched off)
183203
{
184204
#ifdef ANIMATE_ENABLED
185205
animateRandomly();
186206
#endif
187-
setSleep(random(3000, 5000));
188207
}
189208
else
190209
{
191210
// doRest();
192-
setSleep(random(3000, 20000));
211+
isResting = true;
212+
setSleep(random(1000, 5000));
193213
}
194214
}
195215

@@ -219,7 +239,8 @@ void animateRandomly()
219239
// Scale headTiltOffset value between 0 and 180 (inverted) to scale of LEG_IK_MIN and LEG_IK_MAX
220240
float legHeight = map(headTiltOffset, 180, 0, LEG_IK_MIN, LEG_IK_MAX);
221241
// Move legs to that height
222-
servoManager.moveLegs(legHeight, 0);
242+
// servoManager.moveLegs(LEG_IK_MAX, 0);
243+
servoManager.moveServos(PosStand);
223244
shouldMove = true;
224245
#ifdef DEBUG
225246
Serial.print("Moving legs ");

0 commit comments

Comments
 (0)