Arduino Controlled Rotary Stewart Platform

102,980

187

63

Introduction: Arduino Controlled Rotary Stewart Platform

This instructable is about building a Rotary Stewart Platform. It allows to position its moving platform in six degrees of freedom. This specific platform is designed to be able to position a DSLR or any other digital camera.

This version of Stewart Platform uses instead of linear actuators just ordinary hobbyist servos for motion. Whole platform is controlled by an Arduino Uno, it computes all necessary equations to get the platform into right position and also controls servos.

Video of movement of completed platform can be seen here. Quality is not very good, but camera with better picture was at the time of capture on the platform. It was set-up for random position every 4 seconds.

Some informations about platform:

  • weight of load can be up to 2Kg (platform tested with 1.5Kg with no observable problems during moves in whole range of movements), theoretically platform should be able to cope with even higher loads, but it wasn't tested with such load
  • low power consumption - with load of 1kg was consumption of around 5W.
  • very good fineness of moves - smallest possible move is around 1mm
  • perfect ability to repeatedly achieve the same positions.
  • good stability of platform even with big loads.

All source files for platform (templates, Arduino source code, code for communication library can be found here.

Price of platform mostly depends on the price of servos and of the Arduino board. Cutting of parts, all other needed parts cost at most 50$. Total price can be around 150$.

IrDA and LCD with I2C interface were bought from ebay, they are very cheap (together around 10$)

Parts of platform are cutted from acrylic, i used 4mm acrylic.

Needed tools:

  • drill
  • screwdriver
  • tools needed for soldering and creation of PCB for connecting external power supply
  • measuring tools
  • double sided tape

In case of any questions, feel free to contact me.

Step 1: Building Moving Platform

We start by cutting parts from acrylic, here we will use templates from files platform_bot and platform_top. This platform is divided into two parts for better universality, just by changing top part of platform you can adapt it for various purposes. They are put together using screws placed in holes A1-A3.

Dimensions are chosen with respect to size of ordinary DSLR. Platform can be changed to be smaller or bigger.

At denoted places B1-B3 in bottom part of platform it is needed to drill holes which are used for anchoring of connecting rods. On third picture you can see proper way of doing that. These weird deformations in acrylic were caused by using CA glue to fix screws in acrylic.

On top of the moving platform it is necessary to place a piece of rubber or foam and fix it there with double sided tape. It will prevent unwanted rotations and movements of camera on the platform.

Length of connecting rods should be around 12cm and they should be bended as can be seen on picture of completed platform. This bend greatly improves range of movements. Length of rods should be chosen so that the angle between servo arms in horizontal position and the rod is around 70°.

Step 2: Building Base of the Platform

To build base of the platform we will at first need to build PCB for connecting external power supply for the servos. Basic idea behind it and whole schematic of all connections can be seen on the schematic. Layout of the PCB is in the power_board_layout.svg. To all connection points in blue rectangle will go pins for connecting servos. In green area should be sockets for providing power to other accessories such as LCD and IrDA. In purple is shown connection point of power switch. By letter C are denoted positions of capacitors. Last signal cable is connected to ground, this one will be connected to GND socket on the Arduino. Without this connection, servos would run very badly.

Next you should cut main base parts from acrylic based on templates base_bot and base_top. At first, fix the PCB on the bottom part with screws through holes C, and fix three connecting legs (from file servo_arm.dxf) to holes B1-B3. Next place servos on top part, servos should be mounted in holes A0-A5, their signal cables should be led through holes S and W, the right way can be seen on a provided picture, connect all servo connectors to the board, also get all signal cables supposed to go into the Arduino to the top side through holes W. Now fix the connecting leg on top side of base, now it should hold together tightly, if servos can move, fix them with a bit of glue from hot melt glue gun.

Screw spacer screws into holes AD, fix Arduino on them, connect all the cables. Fix the power switch in hole SW. IrDA receiver board is easily fixed with screws through holes I. To fix LCD it is necessary to fix it through helper post - it is fixed on top of the base, LCD is fixed to it from front side. Also connect all cables for LCD and IrDA.

Step 3: Putting It All Together

Cut 6 pieces of servo arms from file servo_arm.dxf. Drill hole on far side with right dimension to be able to screw there nut bolt for ball joint. On the other side drill hole through the arm, place there nut bolt used for fixing it on the servo. This can be seen on a provided picture.

Place all servos into zero position (pulse length of 1500us), then place the arms in horizontal position, tighten the screw. Now is the platform complete and ready to be used.

In source codes, there is file platform.ino, this is main program for the Arduino. Here you have to change few variables with respect to built platform. Many variables are shown on a picture.

MIN and MAX defines - min and max values of servo pulse length

zero[] - pulse lengths in which arms are in completely horizontal position

beta[] - angle between x axis and servo arm

servo_min, servo_max - angle of servo arm in min and max position

servo_mult - values are from technical documentation of the servo, it's pulse length and the resulting angle of rotation corresponding to this pulse length

L1 - servo arm length (from servo rotation point - middle of axis to the center of attachment point - ball joint). In inches

L2 - connecting leg length, in inches

z_home - height of moving platform above base, distance between servo arm and platform.

RD, PD, theta_p, theta_r values - they can be seen on pictures in previous and in this step.

equations for x and y position of servo rotation points on base and platform attachment points, they have to be calculated specificall with respect to desired orientation of x axis. It is just basic goniometry, provided picture can help understand these equations.

Step 4: How Does It Work?

Controlling platform uses inverse kinematics. We know position of base, desired position of platform, then calculate necessary rotation of servos, send them right pulses and its done.

First it is important to define basic position of base rotation points and attachment points of platform, this is bit explained in previous step.

After obtaining values of desired moves, program calculates corresponding position of moving platform attachment points. This is separated into two parts, getting translational vector - vector of movement in x y z axis, rotational matrix - matrix representing values of movement in pitch, roll, yaw, next it is combined in function getrxp, result is new position of platform. From this program finds necessary rotation of each servo, converts this angle into corresponding pulse length and sends it to the servos.

Platform with provided source code listens on serial interface, it accepts at first controlling char which denotes action, then it either executes the action or obtains/sends some data. For easier control of the platform, in src_comm_lib is C++ library for easier interfacing with Arduino, in header file there is explained its usage.

4 People Made This Project!

Recommendations

  • Make It Bridge

    Make It Bridge
  • Big and Small Contest

    Big and Small Contest
  • For the Home Contest

    For the Home Contest

63 Comments

0
DIVYANK TYAGI
DIVYANK TYAGI

Question 5 weeks ago on Step 4

I wanted to know about beta angles used in the code? what is exactly beta angle?

0
zhangyhon
zhangyhon

6 months ago

I tried to build the same platform, and everything was ready. All errors including the program have been fixed. I want to use the communication library to communicate with another software. I want to know how to use it.
The following is another tip of my software about communication.
Use character that have to be send to the receiving device like before and after the axis value.
Use ~a01~ or ~a02~ if you want to insert the x or y axis at this position, declared as the characters above.
For special values or character like return use ~n~ where n is a ascii number between 0 to 255. Return would be ~13~,
Linefeed ~10~.
Example: The device needs a Character "S" for send, the x axis value and then return to proceed:
S~a01~~13~
For XOR checksum use ~c99~ where 99 is a number between 0-99. This number declares the used xor character before ~
which result the sum.
Can you help me?

1
Claudio_Scatena
Claudio_Scatena

2 years ago

Many thanks my friend for your nice project. I took a cue from your work and I created the platform with the controls through the PS3 gamepad.
Greetings

Claudio from Italy

Stewart Platform_1.jpgStewart Platform_3.jpgStewart Platform_4.jpg
0
eliton.lamim
eliton.lamim

Reply 1 year ago

hello, u could send me the arduino code, i'm making the same platform but i'm new to programming. eliton.lamim@gmail.com

0
KeyserS5
KeyserS5

6 years ago

Is that platform having 6 dof?. Correct me if i am wrong, that connecting rod should have one universal joint and one spherical joint right?

0
pramandkumar1513
pramandkumar1513

Reply 3 years ago

You can use female rod end bearing

1
JawadM3
JawadM3

4 years ago

Hello

Any one willing to spare some thoughts over helping me with the code?

Sincerely,

jawad

My Stewart Platform.jpg
0
JawadM3
JawadM3

4 years ago

I downloaded the code from guthub / Thomas KNR for the stewart paltform. Expunged all code lines which were relevant to Ir and LCD. The code compiles fine on Arduino but somewhere has issues whereby pulse outputs do not show up for the 6 rc servos. Any one having a working code, kindly forward it to me. I am a learner only!!!!

Please post it on jawadmajidmalik@gmail.com

Can someone explain what the following routine is about:

//function calculating needed servo rotation value
float getAlpha(int *i) {
static int n;
static float th = 0;
static float q[3], dl[3], dl2;
double min = servo_min;
double max = servo_max;
n = 0;
th = theta_a[*i];
while (n

The design of my platform is a copy picked from the "Instructables".

Sincerely,

Jawad

My Stewart Platform.jpg
1
amirdelavar2095
amirdelavar2095

Question 5 years ago on Introduction

Hi How can help me about Code for Arduino i cant solve it
best regards
a.delavar

exit status 1
Error compiling for board Arduino/Genuino Uno.

20180126_171802.jpg
0
amirdelavar2095
amirdelavar2095

Answer 5 years ago

hi to evry body
i can find problem in Above code
problem is in library
#include ***its ok***
#include ***its ok***
#include ***its ok***
#include ***its ok***
#include *****it is problem & i cant find problem***

have you nice time
a.delavar

GSP.jpg
0
amirdelavar2095
amirdelavar2095

Answer 5 years ago

my code
/*
Copyright (C)

This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.

This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.

You should have received a copy of the GNU General Public License
along with this program. If not, see .*/

#include
#include
#include
#include
#include

//define values of IrDA codes send from used remote control
#define MUTE_BUTTON 0x807F906F
#define STANDBY_ON 0x807F20DF
#define VOL_UP 0x807F609F
#define VOL_DOWN 0x807FA05F
#define DVD 0x807F08F7
#define TV 0x807F8877
#define GAME 0x807F48B7
#define CD 0x807FC837

//define of characters used for control of serial communication ['0'-'8']
#define SETBACKOFF 48
#define SETBACKON 49
#define SETPOSITIONS 50
#define PRINTPOS 51
#define STOPPRINTPOS 52
#define SWITCHIRDA 53
#define SETPOSITIONSINMS 54
#define SWITCHIRDAOFF 55
#define GEPOSITION 56
//defines of LCD pin numbers, most probably they dont have to be changed except of I2C_ADDR which value is neccessary and have to be changed.
#define I2C_ADDR 0x27
#define LCD 1
#define IrDA 1
#define BACKLIGHT_PIN 3
#define En 2
#define Rw 1
#define Rs 0
#define D4 4
#define D5 5
#define D6 6
#define D7 7
//MIN and MAX PWM pulse sizes, they can be found in servo documentation
#define MAX 2200
#define MIN 800

//Positions of servos mounted in opposite direction
#define INV1 1
#define INV2 3
#define INV3 5

//constants for computation of positions of connection points
#define pi 3.14159
#define deg2rad 180/pi
#define deg30 pi/6
//variables used for proper show of positions on LCD
char shown = 0, showPos = 0, useIrda = 0;
unsigned long time;

//variable to store connected LCD
LiquidCrystal_I2C lcd(I2C_ADDR, En, Rw, Rs, D4, D5, D6, D7);
//IrReciever variables
IRrecv irrecv(12); // Receive Ir on digital pin n 12
decode_results results;

//Array of servo objects
Servo servo[6];
//Zero positions of servos, in this positions their arms are perfectly horizontal, in us
static int zero[6] = {1475, 1470, 1490, 1480, 1460, 1490};
//In this array is stored requested position for platform - x,y,z,rot(x),rot(y),rot(z)
static float arr[6] = {0, 0.0, 0, radians(0), radians(0), radians(0)};
//Actual degree of rotation of all servo arms, they start at 0 - horizontal, used to reduce
//complexity of calculating new degree of rotation
static float theta_a[6] = {0.0, 0.0, 0.0, 0.0, 0.0, 0.0};
//Array of current servo positions in us
static int servo_pos[6];
//rotation of servo arms in respect to axis x
const float beta[] = {pi / 2, -pi / 2, -pi / 6, 5 * pi / 6, -5 * pi / 6, pi / 6},
//maximum servo positions, 0 is horizontal position
servo_min = radians(-80), servo_max = radians(80),
//servo_mult - multiplier used for conversion radians->servo pulse in us
//L1-effective length of servo arm, L2 - length of base and platform connecting arm
//z_home - height of platform above base, 0 is height of servo arms
servo_mult = 400 / (pi / 4), L1 = 0.79, L2 = 4.66, z_home = 4.05;
//RD distance from center of platform to attachment points (arm attachment point)
//RD distance from center of base to center of servo rotation points (servo axis)
//theta_p-angle between two servo axis points, theta_r - between platform attachment points
//theta_angle-helper variable
//p[][]=x y values for servo rotation points
//re[]{}=x y z values of platform attachment points positions
//equations used for p and re will affect postion of X axis, they can be changed to achieve
//specific X axis position
const float RD = 2.42, PD = 2.99, theta_p = radians(37.5),
theta_angle = (pi / 3 - theta_p) / 2, theta_r = radians(8),
p[2][6] = {
{
-PD * cos(deg30 - theta_angle), -PD * cos(deg30 - theta_angle),
PD * sin(theta_angle), PD * cos(deg30 + theta_angle),
PD * cos(deg30 + theta_angle), PD * sin(theta_angle)
},
{
-PD * sin(deg30 - theta_angle), PD * sin(deg30 - theta_angle),
PD * cos(theta_angle), PD * sin(deg30 + theta_angle),
-PD * sin(deg30 + theta_angle), -PD * cos(theta_angle)
}
},
re[3][6] = {
{
-RD * sin(deg30 + theta_r / 2), -RD * sin(deg30 + theta_r / 2),
-RD * sin(deg30 - theta_r / 2), RD * cos(theta_r / 2),
RD * cos(theta_r / 2), -RD * sin(deg30 - theta_r / 2),
}, {
-RD * cos(deg30 + theta_r / 2), RD * cos(deg30 + theta_r / 2),
RD * cos(deg30 - theta_r / 2), RD * sin(theta_r / 2),
-RD * sin(theta_r / 2), -RD * cos(deg30 - theta_r / 2),
}, {
0, 0, 0, 0, 0, 0
}
};
//arrays used for servo rotation calculation
//H[]-center position of platform can be moved with respect to base, this is
//translation vector representing this move
static float M[3][3], rxp[3][6], T[3], H[3] = {0, 0, z_home};

void setup() {
//LCD inicialisation and turning on the backlight
#if LCD
lcd.begin(16, 2);
lcd.setBacklightPin(BACKLIGHT_PIN, POSITIVE);
lcd.setBacklight(HIGH);
lcd.home();
#endif

//attachment of servos to PWM digital pins of arduino
servo[0].attach(3, MIN, MAX);
servo[1].attach(5, MIN, MAX);
servo[2].attach(6, MIN, MAX);
servo[3].attach(9, MIN, MAX);
servo[4].attach(10, MIN, MAX);
servo[5].attach(11, MIN, MAX);
//begin of serial communication
Serial.begin(11500);
//putting into base position
setPos(arr);
}

//function calculating needed servo rotation value
float getAlpha(int *i) {
static int n;
static float th = 0;
static float q[3], dl[3], dl2;
double min = servo_min;
double max = servo_max;
n = 0;
th = theta_a[*i];
while (n
//calculation of position of base attachment point (point on servo arm where is leg connected)
q[0] = L1 * cos(th) * cos(beta[*i]) + p[0][*i];
q[1] = L1 * cos(th) * sin(beta[*i]) + p[1][*i];
q[2] = L1 * sin(th);
//calculation of distance between according platform attachment point and base attachment point
dl[0] = rxp[0][*i] - q[0];
dl[1] = rxp[1][*i] - q[1];
dl[2] = rxp[2][*i] - q[2];
dl2 = sqrt(dl[0] * dl[0] + dl[1] * dl[1] + dl[2] * dl[2]);
//if this distance is the same as leg length, value of theta_a is corrent, we return it
if (abs(L2 - dl2)
return th;
}
//if not, we split the searched space in half, then try next value
if (dl2 max = th;
} else {
min = th;
}
n += 1;
if (max == servo_min || min == servo_max) {
return th;
}
th = min + (max - min) / 2;
}
return th;
}

//function calculating rotation matrix
void getmatrix(float pe[])
{
float psi = pe[5];
float theta = pe[4];
float phi = pe[3];
M[0][0] = cos(psi) * cos(theta);
M[1][0] = -sin(psi) * cos(phi) + cos(psi) * sin(theta) * sin(phi);
M[2][0] = sin(psi) * sin(phi) + cos(psi) * cos(phi) * sin(theta);

M[0][1] = sin(psi) * cos(theta);
M[1][1] = cos(psi) * cos(phi) + sin(psi) * sin(theta) * sin(phi);
M[2][1] = cos(theta) * sin(phi);

M[0][2] = -sin(theta);
M[1][2] = -cos(psi) * sin(phi) + sin(psi) * sin(theta) * cos(phi);
M[2][2] = cos(theta) * cos(phi);
}
//calculates wanted position of platform attachment poins using calculated rotation matrix
//and translation vector
void getrxp(float pe[])
{
for (int i = 0; i rxp[0][i] = T[0] + M[0][0] * (re[0][i]) + M[0][1] * (re[1][i]) + M[0][2] * (re[2][i]);
rxp[1][i] = T[1] + M[1][0] * (re[0][i]) + M[1][1] * (re[1][i]) + M[1][2] * (re[2][i]);
rxp[2][i] = T[2] + M[2][0] * (re[0][i]) + M[2][1] * (re[1][i]) + M[2][2] * (re[2][i]);
}
}
//function calculating translation vector - desired move vector + home translation vector
void getT(float pe[])
{
T[0] = pe[0] + H[0];
T[1] = pe[1] + H[1];
T[2] = pe[2] + H[2];
}

unsigned char setPos(float pe[]) {
unsigned char errorcount;
errorcount = 0;
for (int i = 0; i {
getT(pe);
getmatrix(pe);
getrxp(pe);
theta_a[i] = getAlpha(&i);
if (i == INV1 || i == INV2 || i == INV3) {
servo_pos[i] = constrain(zero[i] - (theta_a[i]) * servo_mult, MIN, MAX);
}
else {
servo_pos[i] = constrain(zero[i] + (theta_a[i]) * servo_mult, MIN, MAX);
}
}

for (int i = 0; i {
if (theta_a[i] == servo_min || theta_a[i] == servo_max || servo_pos[i] == MIN || servo_pos[i] == MAX) {
errorcount++;
}
servo[i].writeMicroseconds(servo_pos[i]);
}
return errorcount;
}

//functions used for displaying actual platform position on 16x2 LCD display
#if LCD
void showRot() {
lcd.setCursor(0, 0);
lcd.print("Rot");
lcd.setCursor(12, 0);
lcd.print((int)(arr[3]*deg2rad));
lcd.setCursor(3, 1);
lcd.print((int)(arr[4]*deg2rad));
lcd.setCursor(11, 1);
lcd.print((int)(arr[5]*deg2rad));
}
void showComm() {
if (shown == 0) {
shown = 1;
lcd.setCursor(3, 0);
lcd.print("ation x: ");
lcd.setCursor(0, 1);
lcd.print("y: ");
lcd.setCursor(8, 1);
lcd.print("z: ");
}
}
void clearNr() {
lcd.setCursor(12, 0);
lcd.print(" ");
lcd.setCursor(3, 1);
lcd.print(" ");
lcd.setCursor(11, 1);
lcd.print(" ");

}
void showLoc() {
lcd.setCursor(0, 0);
lcd.print("Loc");
lcd.setCursor(12, 0);
lcd.print((int)(arr[0] * 25.4));
lcd.setCursor(3, 1);
lcd.print((int)(arr[1] * 25.4));
lcd.setCursor(11, 1);
lcd.print((int)(arr[2] * 25.4));
}
#endif

//main control loop, obtain requested action from serial connection, then execute it
void loop()
{

if (Serial.available() > 0) {
int input = Serial.read();
switch (input) {
//action to turn backlight off
case SETBACKOFF:
#if LCD
lcd.setBacklight(LOW);
#endif
break;
//action to turn backlight on
case SETBACKON:
#if LCD
lcd.setBacklight(HIGH);
#endif
break;
//action to change position of platform, obtain 6 values representing desired position
case SETPOSITIONS:
for (int i = 0; i long kk;
while (Serial.available()
;
}
kk = (long)Serial.read();
kk = kk + (Serial.read()
kk = kk + (Serial.read()
kk = kk + (Serial.read()
if (i
arr[i] = (kk / 100) / 25.4;
} else {
arr[i] = radians(kk / 100.0);
}
}
Serial.write(setPos(arr));
Serial.flush();
break;
//enable of showing current position on LCD
case PRINTPOS:
#if LCD
showPos = PRINTPOS;
time = millis();
#endif
break;
//enable of controlling platformy by IrDA remote
case SWITCHIRDA:
#if IrDA
irrecv.enableIRIn();
useIrda = SWITCHIRDA;
#endif
break;
//reserved for future use - possiblity to send just servo timing values
//main control would be executed on communicating partner
case SETPOSITIONSINMS:
for (int i = 0; i long kk;
while (Serial.available()
;
}
kk = (long)Serial.read();
kk = kk | (Serial.read()
kk = kk | (Serial.read()
kk = kk | (Serial.read()
servo[i].writeMicroseconds(kk);
}
break;
//disable of showing current position on LCD
case STOPPRINTPOS:
showPos = STOPPRINTPOS;
shown = 0;
break;
//disable of controlling platformy by IrDA remote
case SWITCHIRDAOFF:
useIrda = SWITCHIRDAOFF;
break;
//return current position of platform
case GEPOSITION:
retPos();
break;
default:
break;
}
}
//helping subroutine to print current position
#if LCD
if (showPos == PRINTPOS) {
static byte act = 0;
showComm();
if (millis() - time
act = 0;
} else if (millis() - time
if (act == 0) {
act = 1;
clearNr();
showRot();
}
} else {
time = millis();
clearNr();
showLoc();
}
}
#endif
//this part is used for IrDA position control
#if IrDA
if (useIrda == SWITCHIRDA && irrecv.decode(&results)) {
static byte val = 0;
switch (results.value) {
case MUTE_BUTTON:
val = 1;
break;
case STANDBY_ON:
val = 0;
break;
case VOL_UP:
if (val
arr[val] += 1;
} else {
arr[val] = radians((arr[val] * deg2rad) + 0.4);
}
break;
case VOL_DOWN:
if (val
arr[val] -= 1;
} else {
arr[val] = radians((arr[val] * deg2rad) - 0.4);
}
break;
case DVD:
val = 2;
break;
case TV:
val = 3;
break;
case GAME:
val = 4;
break;
case CD:
val = 5;
break;
}
setPos(arr);
irrecv.resume(); // Continue receiving
}
#endif

}

void retPos() {
for (int i = 0; i long val;
if (i
val = (long)(arr[i] * 100 * 25.4);
} else {
val = (long)(arr[i] * 100 * deg2rad);
}
Serial.write(val);
Serial.write((val >> 8));
Serial.write((val >> 16));
Serial.write((val >> 24));
Serial.flush();
}
}

0
JawadM3
JawadM3

5 years ago

Good Day, I just saw this post while sifting for a 6 dof platform. I have collected all the hardware and need to make the platform. Please help! Could I have an autocad or similar software drawing for the bottom / top parts. Will get these cut out on Laser thru some local vendors.I await your kind reply.

SIncerely

Jawad Malik

UAE

0
ddaytona1
ddaytona1

6 years ago

Hi. Just viewed this design. How would you incorporate a accelerometer board to make the design into a self leveling platform?

0
锋吉
锋吉

6 years ago

can you help with the design of stewart platform , can tell me the relationship between the platfrom radius ,base radius and height.

0
ThomasKNR
ThomasKNR

Reply 6 years ago

Hi, ratio between size of base and platform is variable - it will affect range of movements, stability, precision (if platform is significantly smaller than base, range increases, stability and precision is decreases and vice versa), i would say size ratio of platform can be around 50-100% of size of base. Height is also variable, it can be shorter, or higher, depends on needs. If legs are very short, it will be harder to construct and range of movements will be limited by joints. If legs are long the upper platform will not be stable, precision will be bad. I would recommend to choose leg length so that in platform zeroposition their angle from base would be somewhere between 45-60°.

0
锋吉
锋吉

Reply 6 years ago

one of the document i read today , it states that In order to avoid singularities, a security margin of 15º between the platform and the links is taken. i dont fully understand what it means. it also gives an example, platform radius is 3cm, then he calculated the base radius and height accordingly .(Base R=7.6cm,H=26cm).

I just start learing stewart platform, a lot things dont understand.
Thank you for explaning my  previous  question.

Capture.PNG
0
SAndeepS155
SAndeepS155

Reply 6 years ago

can i knw the link of this document pls?

0
ThomasKNR
ThomasKNR

Reply 6 years ago

The security margin should prevent legs going straight up, if they are perpendicular to base, it would be unstable and with poor performance in these extreme positions. therefore platform should always by at least bit smaller and the length of legs chosen so they would not reach these extreme positions.