Notifications
Clear all

Novel walking robot

7 Posts
2 Users
3 Likes
1,068 Views
(@patrickwd)
Member
Joined: 2 years ago
Posts: 18
Topic starter  

All

Check out my walking robot. I think it rivals anything Boston Dynamics has put up for novelty.

I have a much longer video but it is a bit boring. I have the actual robot which I expect still works but I haven't had it out for a walk for some years. Will need new batteries all round.

At the time (I did most of the work on it 2015) I was trying to conceive a mechanism which would allow true omni directional movement. This inspired my design which does in fact allow movement in any direction unlike conventional wheels or legs for that matter.

I am looking for a way to take it somewhere or at least get it “out there”.  I have decided that I may be "out of flying hours" to take it anywhere myself and have got into other retirement projects (just took delivery of my excavator - a bit robot like?) I am hoping to inspire some of the contributors to dronebotworkshop to give it a go and progress the project in any number of directions.

I dream of making a momoped jumping version with inverse pendulum solution amongst other things. Full state models and those like things.

The idea is easy to convey and asses. I don't think it would be out of reach (construction or software) of casual makers but the software will I expect stretch the casual programmer (like me). 

My prototype is in the hobby scale but it is readily scalable in many dimensions – size and proportions, speed, number of legs, gait complexity, balance and terrain ability etc. The prototype is very basic and control software rudimentary but sufficient to demonstrate feasibility and flexibility.  It is however simple, fast and robust.  Coolness needs working on but I am sure that would come.

The hardware was made from readily available standard parts (from the RC and Arduino world) and hand tools in a couple of hours.

The idea is very simple based on well known concepts but not put together as I have to my knowledge. 

 My prototype a fully functional large (300mm) octaped was built for about $300 in parts.

I believe that a key assembly the “tri actuator” could be developed into a general purpose product. Does anybody know anything about injection moulded live hinges.  I have a concept 3D model for injection moulded "legs" with full parallel motion.

Unfortunately my documentation is not terrific.  I have drawn up from memory a "concept" schematic which is not complex but is probably very dated.

The main chassis is simply a Perspex disk to which the 24 RC actuators are attached. I have a good drawing of it. Before the days of ready 3D printers.

I don't have drawings as such for the "legs" but can describe their construction. They form a "compliant" style of delta robot geometry.

The software is "just good enough" for demonstration but should be sufficient to duplicate the concepts. It is reasonably well documented. It has two gaits "walking" and "stepping" or should I say stomping (4 up, 4 down move forward and swap all 8 legs over.  Walking was intended to be more like a caterpillar with each leg following 1/8 behind its leader then the last leg stepping forward at which time it would be the only "lifted" leg.  I never got the caffeine levels high enough to get the walking gait to work properly.

(I did a prototype TRIhexaped with only 6 servo channels (2 sets of 3 actuators). It had a much nicer stepping motion smoothly raising each set of legs.  The TRIOctaped just "stomps"  2 X 4 sets run together and they go from up to down without any ramping.  Had a nice algorithm cubing the step position. Overall the TRIhexaped was less stable but it was using the tiny 9gm actuators.)

I stuck with 6 or 8 legs as you don't need to do any balancing which is necessary to make an quadruped like a dog walk.  No reason that you couldn't tackle a 4 legged version if you are up to the balancing algorithms.

I would have killed for the plot facility of the current IDE to debug this code. 

It was controlled through a 6 channel RC handset which provided a good operator interface (and was cheap) but again is probably dated given that WIFI and Bluetooth interfaces to mobile phones are now the thing.

I am not 100% sure which Arduino model I used.  I think it is a Uno.   

0000001 Images DSCF0274 08 10 13
DSCF0277

   

Bottom views

                   

(Spelling was never my thing... I think it is about equally octopod or octaped.  I think it should be octaped but the spell checker doesn't like it?)

I will hold off on the code to see if there is sufficient interest.  Haven't tried posting code here so could be a challenge. It is not huge - just under 1000 lines. Lots of repetition of boring things like calibrations and commentary. There is a bit of it which is nearly beyond my maths - solving the intersection of 3 spheres. I have relied on code from 

Tim Voght http://forums.trossenrobotics.com/tutorials/introduction-129/delta-robot-kinematics-3276/

not sure that my implementation is accurate but it works well enough.

The code I think stressed the UNO speed wise and there are some tricks to help with speed. Integers where possible. Some lookup tables rather than real time trigonometry etc.  I think the porotype was limited by processing speed not the actuators but it would have been close. It has to calculate 24 servo positions for every increment of position.  Some odd delays reading the RC radio so this had to be done infrequently. Debug text also had to be minimised or it would slow things down.  All good fun.

I will be more than willing to assist in any way to get anybody started on the concepts.

I would like things to be called TRIoctaped or TRIhexaped TRImomoped etc to provide some continuity of the idea.

Cheers

Patrick

PWD


   
Inq, THRandell and Inst-Tech reacted
Quote
robotBuilder
(@robotbuilder)
Member
Joined: 5 years ago
Posts: 2042
 

@patrickwd

Cute little robot.  Does it have any sensors?

 


   
ReplyQuote
(@patrickwd)
Member
Joined: 2 years ago
Posts: 18
Topic starter  

@robotbuilder

I did not build any sensors into my robot at the time.  The main game was the platform and that was tricky enough. Plenty of room to mount and interface sensors. Simple interface variables for speed, direction, rotate, step length , step height and splay angle.

Would have been nice to have built in a "relax" mode which would drop all actuators to zero for minimum load. I don't think there is any easy way to disable RC actuators except of course switching off their power.  I had not allowed for this in the schematic but it would have been easy enough to do.  Some power supply modules (e.g. the random one I picked in KiCad for example) have an enable pin which would do the trick.

Cheers

Patrick

PWD


   
ReplyQuote
(@patrickwd)
Member
Joined: 2 years ago
Posts: 18
Topic starter  

All The complete code for the TRIOctaped. By Patrick Durack about 2015.

 

I will start with a full listing for those who can work through the lot.  I will try to give more detailed explanation of the ideas and components later. 

Doesn't want to let me post the .ino file ???

The code formatting didn't appear to help so I have left it as plain text.

Apologies for the spelling - not my thing.

/*
This is the first pass code to control an octapod based on Tri Actuators.
Tri actuators consist of three rotary actuators operating in a form similar to the common delta robot with the exception
that they utilise simple flexible single "legs" which do not incoporate parallel motion dual "legs". They are capable
of placing the "Foot" within a three dimentional space. By sequencing the feet positions unlimited gait actions can be
implemented. As none of the actuators themselves move the feet can move very quickly.

It is fesiable that robots of any leg number could be implemented with the Tri Actuator concept.
Mono, Bi, Tri, Quad and Quint (5?) pedal walking devices are all fesiable but would require dynamic gait stability
which at present is a bit beyond me. Hex and above foot numbers can can be controlled with gaits which are statically
balanced and hence much easier to control. This code is for an octapod for no particular reason other than that I have
tried a hexapod which was sucessfull but the actuators were not sufficiently reliable and the construction inadequate.
It also utilised only 6 control channels which limited the geometry and possible gaits.

The simple gaits implemented in this code consist of 4 up,4 down cyclic actions.

Basic control implemented by RC radio control manipulates 4 variables. Angle, StepHeight, StepLength, Splay angle and Speed.

Further controls are planned including Rotate (To spin the robot either in forward motion or on the same spot.)

The basic step gait involves moving 4 feet down (by an amount set by StepHeight), then moving them all "fordward"
(by an amount set by StepLength). Forward is an angle relative to an arbiary reference Tri Actuator set.
Once the StepLength is reached the "down" feet lift and the other 4 feet then become the down ones. The lifted feet
follow a reverse path "backwards" to be ready for their next step.

Step gait Selet a stepping or a walking gait based on positive or negative step length.
A walking gait is intended to be more realistic where each foot follows the previous foot but delayed by 1/8. When a foot reaches
its limit it is advanced a full step.
This should mean that only one foot is travelling a full step at a time.
It is intended to be a much smoother action.
This mode has not been fully checked out. I.e. it does not work. Gets tangled and falls over.
Nearly works. Never got the caiffne levels high enough to fix. There are a lot of numbers to debug.

The gait is controlled by an incrementing counter (incrementing by an amount established by the Speed input).
This counter is a floating point number which is used to generate using the fractional part the step motions.
Multiples and modifiers are used to implement the gait actions. Speed is dependant on the "loop" rate.

The gait is worked out for the reference foot. As each Tri Actuator in this model is set at an increeasing angle to
the reference a translaction is used to modify the reference foot motion to the relevant angle for each other
actuator so that coordinated parallel stepping results.

The required foot position from the gait calculations is then sent to the inverse kinometric calculations
to calculate the required angle for each of the actuators in each of the Tri Actuator sets.
The kinematic calculations are done in two stages. Firstly the required XYZ position is translated to the
coordinate system for each of the actuators (1 at zero , 2 at 120 and 3 at 270 degrees. Trig calcs are dnoe in radians.)
The coordinates are then passed to the routine which calculates the angle required in its own coordinate system.
If the kinematic calculation fails (position out of valid space) then it needs to return the last angle not say zero.
For each actuator the LastAngle is stored and returned if the calc fails (not implemented).

The required angles are then sent to the servo controller cards via serial interface. There are two servo controller
cards in this model. They are A and B. The relevant actuators are mapped to the applicable card.
Refer to the chassis layout drawing for the actuator naming and the relevant mounting angles.

Each actuator can be assigned its own sero and span. This allows software calibration of each actuator. (As below)
Malipulation of the calibration data is done directly in the code.

There are a lot of calculations to do. The speed is limited by the software. Mechanical response could be droiverna bit faster.

There are a number of support functions to allow setup and calibration of the actuators. Mechanically the actuator arms
fit to the actuator with a spline with a limited number of positions. Mecahnically the arms need to be fitted to the actuators
to achieve as far as possible the same angle for the same actuator signal. Also the Tri Actuator "legs" need to be
made the same length. Some adjustment of the connections is possible.
Four Calibration Modes are provided. Mode 0 is the normal operation mode.
Mode 1 places all actuators at the Minimum position.
Mode 2 places all actuators at the Mid position
Mode 3 places all actuators at the Maximum position.
Mode selection is achieved directly within the code by "commenting out" as required.

*/

 

//Changing the hexapod to Octapod
#include <ServoShield2.h> //Support for the 16 channel servo card

//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// Tri Actuator geometry.

float LegLength = 160; // was D3LL
float ActuatorArmLength = 28; // was D3h
float ActuatorPitchCircleRad = 26; // was D3Ar
float PedCount = 8;// Number of legs
//float pi = 3.141592653; PI is defined

const float sin120 = sqrt(3)/2;
const float cos120 = -0.5;

const float cos45 = 0.707106781;
const float sin45 = 0.707106781;
const float cos90 = 0;
const float sin90 = 1;
const float cos135 = -0.707106781;
const float sin135 = 0.707106781;
const float cos180 = -1;
const float sin180 = 0;
const float cos225 = -0.707106781;
const float sin225 = -0.707106781;
const float cos270 = 0;
const float sin270 = -1;
const float cos315 = 0.707106781;
const float sin315 = -0.707106781;

int I = 0;
float Angle = 0;

//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++

//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// Set up servo calibrations and constants
// Comment out all but the mode you want. Then change the individual servo zero and span
int CalMode = 0; // Normal
//int CalMode = 1; // Calibrate Zero - adjust Zeroxx
//int CalMode = 2; // Calibrate Mid - If zero and span are OK this should be OK
//int CalMode = 3; // Calibrate Max - adjust Spanxx

int MinBound = 600; // Minimum position of any servo
int MaxBound = 2000; // Maximum position of any servo

int InitialPos = 1300; // Default position of any servo

float theta1;
float theta2;
float theta3;

int Zero11 = 700;
long Span11 = 1000;
int Servo11 = 0;
float ServoPos11 = 0;
int Zero12 = 650;
long Span12 = 1000;
int Servo12 = 1;
float ServoPos12 = 0;
int Zero13 = 650;
long Span13 = 1000;
int Servo13 = 2;
float ServoPos13 = 0;

int Zero21 = 650;
long Span21 = 1100;
int Servo21 = 3;
float ServoPos21 = 0;
int Zero22 = 650;
long Span22 = 1100;
int Servo22 = 4;
float ServoPos22 = 0;
int Zero23 = 650;
long Span23 = 1100;
int Servo23 = 5;
float ServoPos23 = 0;

int Zero31 = 700;
long Span31 = 1100;
int Servo31 = 6;
float ServoPos31 = 0;
int Zero32 = 600;
long Span32 = 1100;
int Servo32 = 7;
float ServoPos32 = 0;
int Zero33 = 650;
long Span33 = 1100;
int Servo33 = 8;
float ServoPos33 = 0;

int Zero41 = 600;
long Span41 = 1100;
int Servo41 = 9;
float ServoPos41 = 0;
int Zero42 = 700;
long Span42 = 1100;
int Servo42 = 10;
float ServoPos42 = 0;
int Zero43 = 680;
long Span43 = 1100;
int Servo43 = 11;
float ServoPos43 = 0;

int Zero51 = 750;
long Span51 = 1100;
int Servo51 = 0;
float ServoPos51 = 0;
int Zero52 = 700;
long Span52 = 1100;
int Servo52 = 1;
float ServoPos52 = 0;
int Zero53 = 700;
long Span53 = 1100;
int Servo53 = 2;
float ServoPos53 = 0;

int Zero61 = 800;
long Span61 = 1100;
int Servo61 = 3;
float ServoPos61 = 0;
int Zero62 = 800;
long Span62 = 1100;
int Servo62 = 4;
float ServoPos62 = 0;
int Zero63 = 800;
long Span63 = 1100;
int Servo63 = 5;
float ServoPos63 = 0;

int Zero71 = 750;
long Span71 = 1100;
int Servo71 = 6;
float ServoPos71 = 0;
int Zero72 = 700;
long Span72 = 1100;
int Servo72 = 7;
float ServoPos72 = 0;
int Zero73 = 780;
long Span73 = 1100;
int Servo73 = 8;
float ServoPos73 = 0;

int Zero81 = 750;
long Span81 = 1100;
int Servo81 = 9;
float ServoPos81 = 0;
int Zero82 = 800;
long Span82 = 1100;
int Servo82 = 10;
float ServoPos82 = 0;
int Zero83 = 850;
long Span83 = 1100;
int Servo83 = 11;
float ServoPos83 = 0;

ServoShield2 servosA = ServoShield2(126,50);//Address of 126, using 50Hz mode
ServoShield2 servosB = ServoShield2(127,50);//Address of 127, using 50Hz mode
//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// Radio Control interface variables
float RCPin2 = 2;
float RCPin3 = 3;
float RCPin4 = 4;
float RCPin5 = 5;
float RCPin6 = 6;
float RCPin7 = 7;
float RCMin = 1000;
float RCMax = 1900;
int RCTimeOut = 20000;//Time to wait for a pulse
float RC2;
float RC3;
float RC4;
float RC5;
float RC6;
float RC7;

//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// Misccelaneous variables
int ledPin = 13; // Led Pin
unsigned long time = 0;
//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
//Sequencer timers
unsigned long IncTimeHold; //Remember the last Step Increment run time
long IncInterval = 5; //Period between Step Increments
unsigned long IncRCTimeHold; //Remember the last Step Increment read RC run time
long IncRCInterval = 10; //Period between Step Increment RC reads
unsigned long StepTimeHold; //
long StepInterval = 10; //
unsigned long SetServosTimeHold; //
long SetServosInterval = 10; //
int SkipCount = 0;//Counter to skip iterations don't calculate / output to legs moving slowly
int SkipLim = 16;//Number of skips
//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
//Step Incrementing variables
float Inc = 0.05; //Amount by which step is incremented - set by RC comms. Range -0.1 to +0.1
float IncScale = 0.2;//Scale the RC input by this number
float TravelCounter = 0; //Maintains the travel counter
float StepPos = 0;//Actual current position in step ie. the fractional part of the TravelCounter
int Direction = -1;//Flag for direction in current step
float StepPositionA;
float StepPositionB;

// Step variables
float StepLen = 25; //Set by RC comms. Unit mm Typically 25mm Each Way
float StepLenScale = 60; // +- max step length
float StepHeight = 2.5;//Current step height from PC comms Typically 10mm
float StepHeightScale = 20; // +- max step height
float RotateLen = 0; //Rotate amount set by RC
float RotateScale = 30;//Scale for rotate step length
float StepHeightA = 0;//Current height of the A feet
float StepHeightB = 0;//Current height of the B feet
float IntX = 0; //Intermediate X calc
float IntY = 0; //Intermediate Y calc
float IntZ = 0; //Intermediate Z calc
float KeyStepAX = 0; // Key actuator A set
float KeyStepAY = 0;
float KeyStepAZ = 0;
float KeyStepBX = 0; // Key Actuator B set
float KeyStepBY = 0;
float KeyStepBZ = 0;
float KeyStepX = 0;
float KeyStepY = 0;
float KeyStepZ = 0;
float StrideAng = 0; //Read from RC control
float SplayAngle = 0;//
float SplayAngleScale = 20;
int ChangeGaitFlag = 0;//Detect change of gait and set step position to 0

float ServoOffset = 20; // An offset angle to adjust the servo zero. Should not be necessary but
// inverse kinematic function appears to have an offset.
// use to set the average servo angle

// Walking variables
float WalkPosDir[8][2]; //Set up an array for each leg - Position

//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++

void setup()
{
Serial.begin(9600);
Serial.println("Hello, I am a TriOctaapod! I think");

Serial.println ("TravelCounter, i, StepPos, WalkPosDir[i][1], (WalkPosDir[i][2]), ");

servosA.start();
servosB.start();
for (int servo = 0; servo < 16; servo++)//Initialize all 16 A servos
{
servosA.setbounds(servo, MinBound, MaxBound); //Set the minimum and maximum pulse duration of the A servos
servosA.setposition(servo, InitialPos); //Set the initial position of the A servos
servosB.setbounds(servo, MinBound, MaxBound); //Set the minimum and maximum pulse duration of the B servos
servosB.setposition(servo, InitialPos); //Set the initial position of the B servos
}

// Set up RC pins for input
pinMode (RCPin2, INPUT); //Angle
pinMode (RCPin3, INPUT); //Step Height
pinMode (RCPin4, INPUT); //Step Length
pinMode (RCPin5, INPUT); //Speed
pinMode (RCPin6, INPUT); //xx
pinMode (RCPin7, INPUT); //xxx

time = micros();

// Read all RC channels. Note that if the radio is not on then this takes a long time.
// Even when a pulse is received it takes a while. Only read the radio when strictly necessary.
//RCin2(); RCin3(); RCin4(); RCin5();RCin6(); RCin7(); Don't read these while testing - 6 second delay.

}
//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
void loop(){

sequencer();

}
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++
void sequencer(){
time = micros();
// if (time - StepTimeHold > StepInterval){ stepper(); TravelInc(); StepTimeHold = time; } //store last time
if (time - IncTimeHold > IncInterval){ // if (ChangeGaitFlag == 1)
if (StepLen > 0){ // Select stepping or walking mode
TravelInc();} else {
TravelIncWalk();}
IncTimeHold = time;
} //store last time

//if (time - IncRCTimeHold > IncRCInterval){ SetInc(); TravelInc(); Stepper(); IncRCTimeHold = time; } //store last time
if (StepLen > 0){ // Step gait Selet a stepping or a walking gait based on positive or negative step length.

if (time - IncRCTimeHold > IncRCInterval){
SetInc();
//TravelInc();
Stepper();
IncRCTimeHold = time; //store last time
}
} else //Walk gait
{
if (time - IncRCTimeHold > IncRCInterval){
SetInc();
//TravelIncWalk();
Walker();
IncRCTimeHold = time; //store last time
}
}

// if (time - StepTimeHold > StepInterval){ Stepper(); StepTimeHold = time; } //store last time
if (time - SetServosTimeHold > SetServosInterval){
SetServos();
SetServosTimeHold = time;
} //store last time
}
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++

void TravelInc(){ //Travel incrementer. Moves travel position by the increment
//RC setting which can be positive or negative
//Generates inverse A and B unscaled step positions.
//Also generates Direction which can be used for
//raise / lower the A and *-1 the B feet
//Serial.print (" TravelInc(), "); Serial.println (micros());
TravelCounter = TravelCounter + Inc;
long IntTravelCounter = abs(TravelCounter);
StepPos = abs(TravelCounter) - IntTravelCounter; // Get the fractional part

if (StepPos > 0.5) {
StepPos = 1 - StepPos;
Direction = -1;
}
else {
Direction = 1;
}
StepPositionA = StepPos * 4 -1;
StepPositionB = StepPositionA * -1;
// Serial.print (" Inc, "); Serial.print (Inc);
// Serial.print (" TravelCounter, "); Serial.print (TravelCounter);
// Serial.print (" StepPos, "); Serial.print (StepPos);
// Serial.print (" Direction, "); Serial.print (Direction);
// Serial.print (" StepPositionA, "); Serial.print ( StepPositionA);
// Serial.print (" StepPositionB, "); Serial.println ( StepPositionB);
}

//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++=

void TravelIncWalk(){ //Travel incrementer. Moves travel position by the increment
//RC setting which can be positive or negative
//Generates Rolling walk n-1 forward nth flips back from StepLim
//Also generates Directions which can be used for
//raise / lower the appropriate feet
//Serial.print (" TravelInc(), "); Serial.println (micros());
float StepLim = 0.875; // Roll back position

TravelCounter = TravelCounter + Inc;

Serial.print (TravelCounter);
Serial.print (" , ");

float TC = TravelCounter ;
int i;
for (i = 0; i < 8; i = i + 1) {

long IntTravelCounter = abs(TC);
StepPos = abs(TC) - IntTravelCounter; // Get the fractional part

if (StepPos < StepLim) //
{
WalkPosDir[i][1] = (StepPos * PedCount/(PedCount-1))*2 -1; // 8/7
WalkPosDir[i][2] = 1;
Direction = 1;

}
else
{
WalkPosDir[i][1] = (1 - (StepPos-(7.0/8.0)) * PedCount)*2 -1;
WalkPosDir[i][2] = -1;

Direction = 1;
}

//TravelCounter, i, StepPos, WalkPosDir[i][1], (WalkPosDir[i][2])

Serial.print (", ");
Serial.print (i);
Serial.print (" , ");
Serial.print (StepPos,4);
Serial.print (" , ");
Serial.print (WalkPosDir[i][1]);
Serial.print (" , ");
Serial.print (WalkPosDir[i][2]);

TC = TC + 1/PedCount;
}
Serial.println();
/*
Serial.print (" StepPos, ");
Serial.print (StepPos,3);
Serial.print (" WalkPosDir[0][1], ");
Serial.print (WalkPosDir[0][1],3);
Serial.print (" WalkPosDir[0][2], ");
Serial.print (WalkPosDir[0][2]);

Serial.print (" WalkPosDir[7][1], ");
Serial.print (WalkPosDir[7][1],3);
Serial.print (" WalkPosDir[7][2], ");
Serial.println (WalkPosDir[7][2]);
*/
StepPositionA = StepPos * 4 -1;
StepPositionB = StepPositionA * -1;
// Serial.print (" Inc, "); Serial.print (Inc);
// Serial.print (" TravelCounter, "); Serial.print (TravelCounter);
// Serial.print (" StepPos, "); Serial.print (StepPos);
// Serial.print (" Direction, "); Serial.print (Direction);
// Serial.print (" StepPositionA, "); Serial.print ( StepPositionA);
// Serial.print (" StepPositionB, "); Serial.println ( StepPositionB);
}

//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
void SetInc(){ //Set step and other RC variables
RCin4(); // LHS joystick forward / back
StepLen = RC4*StepLenScale;
// Serial.print (" StepLen, "); Serial.print (StepLen);

RCin2(); // LHS joystick left right
StrideAng = RC2 * 4 * PI; //angle in radians

RCin3(); // RHS joystick forward / back
Inc = RC3*IncScale; // Set scaled increment value.
// Serial.print (" Inc, "); Serial.println (Inc,4);
RCin5(); // RHS joystick forward / back I don't think so??
RotateLen = RC5*RotateScale; // Set scaled rotate value.
//Serial.print (" RotateLen, "); Serial.println (RotateLen);

RCin6(); // LHS knob
StepHeight = RC6 * StepHeightScale;
//Serial.print (" StepHeight, "); Serial.println (StepHeight);

RCin7(); // RHS Knob
SplayAngle = RC7*SplayAngleScale;//

//Inc = 0.01;
//Serial.print (" StrideAngle, "); Serial.println (StrideAng);
}
//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
void Stepper(){ // This function takes the step position and calculates the X.Y.Z
// for each foot set

// Key stride variables for the A sets
KeyStepAX = StepPositionA * StepLen * cos(StrideAng);
KeyStepAY = StepPositionA * StepLen * sin(StrideAng) ; // For the key actuator set Y = 0
KeyStepAZ = LegLength + (Direction * StepHeight);
//Serial.print (" KeyStepAZ, "); Serial.println (KeyStepAZ);
IntX = KeyStepAX + StepPositionA*RotateLen;
IntY = KeyStepAY;
IntZ = KeyStepAZ;

//Inverse Kinematic Calcs for the A1 actuator set 11,12,13 at 0 Degrees
IKActCalc(IntX,IntY,IntZ);
ServoPos11 = ServoOffset - theta1 + SplayAngle;
ServoPos12 = ServoOffset - theta2;
ServoPos13 = ServoOffset - theta3;

IntX = KeyStepAX*cos90 - KeyStepAY*sin90 + StepPositionA*RotateLen;
IntY = KeyStepAX*sin90 + KeyStepAY*cos90;
IntZ = KeyStepAZ;

//Inverse Kinematic Calcs for the A2 actuator set 31,32,33 at 90Degrees
IKActCalc(IntX,IntY,IntZ);

ServoPos31= ServoOffset - theta1 + SplayAngle;
ServoPos32= ServoOffset - theta2;
ServoPos33= ServoOffset - theta3;

IntX = KeyStepAX*cos180 + KeyStepAY*sin180 + StepPositionA*RotateLen;
IntY = KeyStepAY*cos180 - KeyStepAX*sin180;
IntZ = KeyStepAZ;

//Inverse Kinematic Calcs for the A3 actuator set 51,52,53 at 180Degrees
//IKActCalc(KeyStepAX*cos180 + KeyStepAY*sin180, KeyStepAY*cos180 - KeyStepAX*sin180,KeyStepAZ);
IKActCalc(IntX,IntY,IntZ);
ServoPos51= ServoOffset - theta1 + SplayAngle;
ServoPos52= ServoOffset - theta2;
ServoPos53= ServoOffset - theta3;

IntX = KeyStepAX*cos90 + KeyStepAY*sin90 + StepPositionA*RotateLen;
IntY = KeyStepAY*cos90 - KeyStepAX*sin90;
IntZ = KeyStepAZ;

//Inverse Kinematic Calcs for the A4 actuator set 71,72,73 at 270Degrees ???!@%^&* don't know why 270 doesn't work
//IKActCalc(KeyStepAX*cos90 + KeyStepAY*sin90, KeyStepAY*cos90 - KeyStepAX*sin90,KeyStepAZ);
IKActCalc(IntX,IntY,IntZ);
ServoPos71= ServoOffset - theta1 + SplayAngle;
ServoPos72= ServoOffset - theta2;
ServoPos73= ServoOffset - theta3;

// Key stride variables for the B sets
KeyStepBX = StepPositionB * StepLen * cos(StrideAng);
KeyStepBY = StepPositionB * StepLen * sin(StrideAng); // For the key actuator set Y = 0
KeyStepBZ = LegLength - (Direction * StepHeight);
//Serial.print (" KeyStepBZ, "); Serial.println (KeyStepBZ);

IntX = KeyStepBX*cos45 - KeyStepBY*sin45 + StepPositionB*RotateLen;
IntY = KeyStepBX*sin45 + KeyStepBY*cos45;
IntZ = KeyStepBZ;

//Inverse Kinematic Calcs for the B1 actuator set 21,22,23 at 45 Degrees
//IKActCalc(KeyStepBX*cos45 - KeyStepBY*sin45, KeyStepBX*sin45 + KeyStepBY*cos45,KeyStepBZ);
IKActCalc(IntX,IntY,IntZ);
ServoPos21 = ServoOffset - theta1 + SplayAngle;
ServoPos22 = ServoOffset - theta2;
ServoPos23 = ServoOffset - theta3;

IntX = KeyStepBX*cos135 - KeyStepBY*sin135 + StepPositionB*RotateLen;
IntY = KeyStepBX*sin135 + KeyStepBY*cos135;
IntZ = KeyStepBZ;

//Inverse Kinematic Calcs for the B2 actuator set 41,42,43 at 135 Degrees
//IKActCalc(KeyStepBX*cos135 - KeyStepBY*sin135, KeyStepBX*sin135 + KeyStepBY*cos135,KeyStepBZ);
IKActCalc(IntX,IntY,IntZ);
ServoPos41 = ServoOffset - theta1 + SplayAngle;
ServoPos42 = ServoOffset - theta2;
ServoPos43 = ServoOffset - theta3;

IntX = KeyStepBX*cos225 - KeyStepBY*sin225 + StepPositionB*RotateLen;
IntY = KeyStepBX*sin225 + KeyStepBY*cos225;
IntZ = KeyStepBZ;

//Inverse Kinematic Calcs for the B3 actuator set 61,62,63 at 225 Degrees
//IKActCalc(KeyStepBX*cos225 - KeyStepBY*sin225, KeyStepBX*sin225 + KeyStepBY*cos225,KeyStepBZ);
IKActCalc(IntX,IntY,IntZ);
ServoPos61 = ServoOffset - theta1 + SplayAngle;
ServoPos62 = ServoOffset - theta2;
ServoPos63 = ServoOffset - theta3;

IntX = KeyStepBX*cos315 - KeyStepBY*sin315 + StepPositionB*RotateLen;
IntY = KeyStepBX*sin315 + KeyStepBY*cos315;
IntZ = KeyStepBZ;

//Inverse Kinematic Calcs for the B4 actuator set 81,82,83 at 315 Degrees
//IKActCalc(KeyStepBX*cos315 - KeyStepBY*sin315, KeyStepBX*sin315 + KeyStepBY*cos315,KeyStepBZ);
IKActCalc(IntX,IntY,IntZ);
ServoPos81 = ServoOffset - theta1 + SplayAngle;
ServoPos82 = ServoOffset - theta2;
ServoPos83 = ServoOffset - theta3;

}//end stepper

//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++

 

 

//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
void Walker(){ // This function takes the step position and calculates the X.Y.Z
// for each foot set

if (SkipCount > SkipLim) {SkipCount = 0;}

if (SkipCount == 0 || WalkPosDir[0][2] == -1)
{
KeyStepX = WalkPosDir[0][1] * StepLen * cos(StrideAng);
KeyStepY = WalkPosDir[0][1] * StepLen * sin(StrideAng) ;
KeyStepZ = LegLength + (WalkPosDir[0][2] * StepHeight);
//Serial.print (" KeyStepAZ, "); Serial.println (KeyStepAZ);
IntX = KeyStepX; //+ StepPositionA*RotateLen;
IntY = KeyStepY;
IntZ = KeyStepZ;

//Inverse Kinematic Calcs for the A1 actuator set 11,12,13 at 0 Degrees
IKActCalc(IntX,IntY,IntZ);
ServoPos11 = ServoOffset - theta1 + SplayAngle;
ServoPos12 = ServoOffset - theta2;
ServoPos13 = ServoOffset - theta3;
}

if (SkipCount == 0 || WalkPosDir[2][2] == -1)
{
KeyStepX = WalkPosDir[2][1] * StepLen * cos(StrideAng);
KeyStepY = WalkPosDir[2][1] * StepLen * sin(StrideAng) ;
KeyStepZ = LegLength + (WalkPosDir[2][2] * StepHeight);

IntX = KeyStepX*cos90 - KeyStepY*sin90; //+ StepPositionA*RotateLen;
IntY = KeyStepX*sin90 + KeyStepY*cos90;
IntZ = KeyStepZ;

//Inverse Kinematic Calcs for the actuator set 31,32,33 at 90Degrees
IKActCalc(IntX,IntY,IntZ);

ServoPos31= ServoOffset - theta1 + SplayAngle;
ServoPos32= ServoOffset - theta2;
ServoPos33= ServoOffset - theta3;
}

if (SkipCount == 0 || WalkPosDir[4][2] == -1)
{
KeyStepX = WalkPosDir[4][1] * StepLen * cos(StrideAng);
KeyStepY = WalkPosDir[4][1] * StepLen * sin(StrideAng) ; // For the key actuator set Y = 0
KeyStepZ = LegLength + (WalkPosDir[4][2] * StepHeight);

IntX = KeyStepX*cos180 + KeyStepY*sin180; //+ StepPositionA*RotateLen;
IntY = KeyStepY*cos180 - KeyStepX*sin180;
IntZ = KeyStepZ;

//Inverse Kinematic Calcs for the actuator set 51,52,53 at 180Degrees
//IKActCalc(KeyStepAX*cos180 + KeyStepAY*sin180, KeyStepAY*cos180 - KeyStepAX*sin180,KeyStepAZ);
IKActCalc(IntX,IntY,IntZ);
ServoPos51= ServoOffset - theta1 + SplayAngle;
ServoPos52= ServoOffset - theta2;
ServoPos53= ServoOffset - theta3;
}

if (SkipCount == 0 || WalkPosDir[6][2] == -1)
{
KeyStepX = WalkPosDir[6][1] * StepLen * cos(StrideAng);
KeyStepY = WalkPosDir[6][1] * StepLen * sin(StrideAng);
KeyStepZ = LegLength + (WalkPosDir[6][2] * StepHeight);

IntX = KeyStepX*cos90 + KeyStepY*sin90; //+ StepPositionA*RotateLen;
IntY = KeyStepY*cos90 - KeyStepX*sin90;
IntZ = KeyStepZ;

//Inverse Kinematic Calcs for the actuator set 71,72,73 at 270Degrees ???!@%^&* don't know why 270 doesn't work
//IKActCalc(KeyStepAX*cos90 + KeyStepAY*sin90, KeyStepAY*cos90 - KeyStepAX*sin90,KeyStepAZ);
IKActCalc(IntX,IntY,IntZ);
ServoPos71= ServoOffset - theta1 + SplayAngle;
ServoPos72= ServoOffset - theta2;
ServoPos73= ServoOffset - theta3;
}

if (SkipCount == 0 || WalkPosDir[1][2] == -1)
{
KeyStepX = WalkPosDir[1][1] * StepLen * cos(StrideAng);
KeyStepY = WalkPosDir[1][1] * StepLen * sin(StrideAng);
KeyStepZ = LegLength + (WalkPosDir[1][2] * StepHeight);

//Serial.print (" KeyStepBZ, "); Serial.println (KeyStepBZ);

IntX = KeyStepX*cos45 - KeyStepY*sin45; // + StepPositionB*RotateLen;
IntY = KeyStepX*sin45 + KeyStepY*cos45;
IntZ = KeyStepZ;

//Inverse Kinematic Calcs for the actuator set 21,22,23 at 45 Degrees
//IKActCalc(KeyStepBX*cos45 - KeyStepBY*sin45, KeyStepBX*sin45 + KeyStepBY*cos45,KeyStepBZ);
IKActCalc(IntX,IntY,IntZ);
ServoPos21 = ServoOffset - theta1 + SplayAngle;
ServoPos22 = ServoOffset - theta2;
ServoPos23 = ServoOffset - theta3;
}

if (SkipCount == 0 || WalkPosDir[3][2] == -1)
{
KeyStepX = WalkPosDir[3][1] * StepLen * cos(StrideAng);
KeyStepY = WalkPosDir[3][1] * StepLen * sin(StrideAng) ;
KeyStepZ = LegLength + (WalkPosDir[3][2] * StepHeight);

IntX = KeyStepX*cos135 - KeyStepY*sin135; // + StepPositionB*RotateLen;
IntY = KeyStepX*sin135 + KeyStepY*cos135;
IntZ = KeyStepZ;

//Inverse Kinematic Calcs for the actuator set 41,42,43 at 135 Degrees
//IKActCalc(KeyStepBX*cos135 - KeyStepBY*sin135, KeyStepBX*sin135 + KeyStepBY*cos135,KeyStepBZ);
IKActCalc(IntX,IntY,IntZ);
ServoPos41 = ServoOffset - theta1 + SplayAngle;
ServoPos42 = ServoOffset - theta2;
ServoPos43 = ServoOffset - theta3;
}

if (SkipCount == 0 || WalkPosDir[5][2] == -1)
{
KeyStepX = WalkPosDir[5][1] * StepLen * cos(StrideAng);
KeyStepY = WalkPosDir[5][1] * StepLen * sin(StrideAng) ; // For the key actuator set Y = 0
KeyStepZ = LegLength + (WalkPosDir[5][2] * StepHeight);

IntX = KeyStepX*cos225 - KeyStepY*sin225; // + StepPositionB*RotateLen;
IntY = KeyStepX*sin225 + KeyStepY*cos225;
IntZ = KeyStepZ;

//Inverse Kinematic Calcs for the actuator set 61,62,63 at 225 Degrees
//IKActCalc(KeyStepBX*cos225 - KeyStepBY*sin225, KeyStepBX*sin225 + KeyStepBY*cos225,KeyStepBZ);
IKActCalc(IntX,IntY,IntZ);
ServoPos61 = ServoOffset - theta1 + SplayAngle;
ServoPos62 = ServoOffset - theta2;
ServoPos63 = ServoOffset - theta3;
}

if (SkipCount == 0 || WalkPosDir[7][2] == -1)
{
KeyStepX = WalkPosDir[7][1] * StepLen * cos(StrideAng);
KeyStepY = WalkPosDir[7][1] * StepLen * sin(StrideAng) ;
KeyStepZ = LegLength + (WalkPosDir[7][2] * StepHeight);

IntX = KeyStepX*cos315 - KeyStepY*sin315; // + StepPositionB*RotateLen;
IntY = KeyStepX*sin315 + KeyStepY*cos315;
IntZ = KeyStepZ;

//Inverse Kinematic Calcs for the B4 actuator set 81,82,83 at 315 Degrees
//IKActCalc(KeyStepBX*cos315 - KeyStepBY*sin315, KeyStepBX*sin315 + KeyStepBY*cos315,KeyStepBZ);
IKActCalc(IntX,IntY,IntZ);
ServoPos81 = ServoOffset - theta1 + SplayAngle;
ServoPos82 = ServoOffset - theta2;
ServoPos83 = ServoOffset - theta3;
}

SkipCount ++;

}//end walker

//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++

void IKActCalc(float x0,float y0,float z0)
//This function will return the angle for actuators 1,2,3
//This code works - just.
//Things which need to be fixed include scaling to zero degrees.
{
theta1 = IKCalc(x0,y0,z0,theta1);
theta2 = IKCalc(x0*cos120 + y0*sin120, y0*cos120 - x0*sin120,z0,theta2);
theta3 = IKCalc(x0*cos120 - y0*sin120, y0*cos120 + x0*sin120,z0,theta3);
}
//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// Kinametic solution

float IKCalc(float x0, float y0, float z0, float lasta ) // Kinametic solution
{
// Find the actuator angle to achieve a given foot position.
//
// Thanks to Tim Voght http://forums.trossenrobotics.com/tutorials/introduction-129/delta-robot-kinematics-3276/
//
//x0 xcoord of foot
//y0 ycoord of foot
//z0 zcoord of foot
//lasta result of last good calc for this actuator. Return this is calc fails.
int err = 1; //default to good

float a = (x0*x0 + y0*y0 + z0*z0 + ActuatorArmLength*ActuatorArmLength -
LegLength*LegLength - ActuatorPitchCircleRad*ActuatorPitchCircleRad)/(2*z0);

float b = (-ActuatorPitchCircleRad-y0)/z0;

float d = -(a+b*-ActuatorPitchCircleRad)*(a+b*-ActuatorPitchCircleRad)+ ActuatorArmLength
* (b*b*ActuatorArmLength + ActuatorArmLength);

if (d < 0) err = -1;//circles do not intersect

float yj = (-ActuatorPitchCircleRad - a*b -sqrt(d))/(b*b +1);
float zj = a + b*yj;

float theta = 180.0 * atan (-zj/(-ActuatorPitchCircleRad - yj))/PI + ((yj>-ActuatorPitchCircleRad)?180.0:0.0);

//Serial.print (" theta deg, "); Serial.print (theta); Serial.print (" err, "); Serial.println (err);

if(err == 1){
return theta;
}
else {
digitalWrite(ledPin, HIGH); // sets the LED on
delay(10); // waits for a second
digitalWrite(ledPin, LOW); // sets the LED off
return lasta;
}

} //End Function D3aCalcK

//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++

void SetServos(){
switch (CalMode) { // Serts up the Calibration Mode
case 0: // Normal - pass through the gait position
break;
case 1: // Set Servos to 0
ServoPos11=ServoPos12=ServoPos13=0;
ServoPos21=ServoPos22=ServoPos23=0;
ServoPos31=ServoPos32=ServoPos33=0;
ServoPos41=ServoPos42=ServoPos43=0;
ServoPos51=ServoPos52=ServoPos53=0;
ServoPos61=ServoPos62=ServoPos63=0;
ServoPos71=ServoPos72=ServoPos73=0;
ServoPos81=ServoPos82=ServoPos83=0;

break;
case 2: // Set Servos to 50%
ServoPos11=ServoPos12=ServoPos13=50;
ServoPos21=ServoPos22=ServoPos23=50;
ServoPos31=ServoPos32=ServoPos33=50;
ServoPos41=ServoPos42=ServoPos43=50;
ServoPos51=ServoPos52=ServoPos53=50;
ServoPos61=ServoPos62=ServoPos63=50;
ServoPos71=ServoPos72=ServoPos73=50;
ServoPos81=ServoPos82=ServoPos83=50;
break;
case 3: // Set Servos to 100%
ServoPos11=ServoPos12=ServoPos13=100;
ServoPos21=ServoPos22=ServoPos23=100;
ServoPos31=ServoPos32=ServoPos33=100;
ServoPos41=ServoPos42=ServoPos43=100;
ServoPos51=ServoPos52=ServoPos53=100;
ServoPos61=ServoPos62=ServoPos63=100;
ServoPos71=ServoPos72=ServoPos73=100;
ServoPos81=ServoPos82=ServoPos83=100;
break;
}

servosA.setposition(Servo11, (Zero11 + Span11*ServoPos11/100));
servosA.setposition(Servo12, (Zero12 + Span12*ServoPos12/100));
servosA.setposition(Servo13, (Zero13 + Span13*ServoPos13/100));

servosA.setposition(Servo21, (Zero21 + Span21*ServoPos21/100));
servosA.setposition(Servo22, (Zero22 + Span22*ServoPos22/100));
servosA.setposition(Servo23, (Zero23 + Span23*ServoPos23/100));

servosA.setposition(Servo31, (Zero31 + Span31*ServoPos31/100));
servosA.setposition(Servo32, (Zero32 + Span32*ServoPos32/100));
servosA.setposition(Servo33, (Zero33 + Span33*ServoPos33/100));

servosA.setposition(Servo41, (Zero41 + Span41*ServoPos41/100));
servosA.setposition(Servo42, (Zero42 + Span42*ServoPos42/100));
servosA.setposition(Servo43, (Zero43 + Span43*ServoPos43/100));

servosB.setposition(Servo51, (Zero51 + Span51*ServoPos51/100));
servosB.setposition(Servo52, (Zero52 + Span52*ServoPos52/100));
servosB.setposition(Servo53, (Zero53 + Span53*ServoPos53/100));

servosB.setposition(Servo61, (Zero61 + Span61*ServoPos61/100));
servosB.setposition(Servo62, (Zero62 + Span62*ServoPos62/100));
servosB.setposition(Servo63, (Zero63 + Span63*ServoPos63/100));

servosB.setposition(Servo71, (Zero71 + Span71*ServoPos71/100));
servosB.setposition(Servo72, (Zero72 + Span72*ServoPos72/100));
servosB.setposition(Servo73, (Zero73 + Span73*ServoPos73/100));

servosB.setposition(Servo81, (Zero81 + Span81*ServoPos81/100));
servosB.setposition(Servo82, (Zero82 + Span82*ServoPos82/100));
servosB.setposition(Servo83, (Zero83 + Span83*ServoPos83/100));

}
//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++

//+++++++++++++++++++++++++++++++++++++++++++++++++++++
// Read Radio Control variables.
void RCin2(){ // 2 LHS joystick left right
float RC = 1000;
RC = pulseIn(RCPin2, HIGH, RCTimeOut);
if (RC < 1000){
RC = 1000;
}
RC2 = .5*((RC-RCMin)/(RCMax - RCMin)-.5); //Inc -.5 to +.5
}

void RCin3(){ // 3 RHS joystick forward / back
float RC = 1000;
RC = pulseIn(RCPin3, HIGH,RCTimeOut);
if (RC < 1000){
RC = 1000;
}
RC3 = -1 + 2*(RC-RCMin)/(RCMax - RCMin); // -1 to 1
}

void RCin4(){ // 4 LHS joystick forward / back
float RC = 1000;
RC = pulseIn(RCPin4, HIGH,RCTimeOut);
if (RC < 1000){
RC = 1000;
}
RC4 = -1 + 2*(RC-RCMin)/(RCMax - RCMin);
}

float RCin5(){ // Rotate angle RHS joystick Left to right
float RC = 1000;
float RCin = 1000;
RC = pulseIn(RCPin5, HIGH,RCTimeOut);
if (RC < 1000){
RC = 1000;
}
RC5 = -1 + 2*(RC-RCMin)/(RCMax - RCMin); // -1 to 1 note this control is inverse
// (RHS = 0 LHS = 1) out of the transmitter
RC5 = RC5*-1;
}

float RCin6(){ // 6 LHS knob
float RC = 1000;
float RCin = 1000;
RC = pulseIn(RCPin6, HIGH,RCTimeOut);
if (RC < 1000){
RC = 1000;
}
RC6 = (RC-RCMin)/(RCMax - RCMin); // 0 to 1
// Serial.print (" RC6, "); Serial.println (RC6);
}

float RCin7(){ // 7 RHS knob
float RC = 1000;
float RCin = 1000;
RC = pulseIn(RCPin7, HIGH,RCTimeOut);
if (RC < 1000){
RC = 1000;
}
RC7 = -1 + 2*(RC-RCMin)/(RCMax - RCMin);
}
//++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++

 

PWD


   
ReplyQuote
robotBuilder
(@robotbuilder)
Member
Joined: 5 years ago
Posts: 2042
 

   
ReplyQuote
(@patrickwd)
Member
Joined: 2 years ago
Posts: 18
Topic starter  

All

I am curious how little interest there has been in my project.  I would have thought it was on topic.  Arduino controlled, hobby scale and cost, novel and huge scope for improvement.

Anybody got any clues on how to stir up a bit more interest?

I am off bush for a couple of weeks (I am often in the bush) and may not be on line often but I am looking forward to any feedback.

Thanks Patrick

PWD


   
ReplyQuote
robotBuilder
(@robotbuilder)
Member
Joined: 5 years ago
Posts: 2042
 

@patrickwd 

It certainly makes the creepy sound of the Boston Dynamics robots a version of which I think was used in a fantasy War Of The Worlds where the spiel claimed it to be based on H.G.Wells novel but the premise was very different.

SBS series

Interest and something to say are different things. Only some of us are interested in robots and my interest is more in the AI although I would like to have the money to build a "real" robot that could carry out practical tasks.

So thank you for posting and let me assure you it is interesting to me as a working robot project. What do you plan to do beyond having remote control of its actions?

I used to like "going bush" although all the mallee where I used to roam has been cleared with some of it being used to grow grapes and most left barren for the soil to blow away in the wind.

 

 


   
ReplyQuote