Skip to content

Commit cacba82

Browse files
committed
Added support for polar cylindrical coordinates.
1 parent 8d99cbb commit cacba82

File tree

3 files changed

+44
-1
lines changed

3 files changed

+44
-1
lines changed

keywords.txt

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,11 @@ openGripper KEYWORD2
1717
closeGripper KEYWORD2
1818
gotoPoint KEYWORD2
1919
goDirectlyTo KEYWORD2
20+
gotoPointCylinder KEYWORD2
21+
goDirectlyToCylinder KEYWORD2
2022
isReachable KEYWORD2
2123
getX KEYWORD2
2224
getY KEYWORD2
2325
getZ KEYWORD2
26+
getR KEYWORD2
27+
getTheta KEYWORD2

meArm.cpp

Lines changed: 30 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -61,7 +61,8 @@ void meArm::begin(int pinBase, int pinShoulder, int pinElbow, int pinGripper) {
6161
_elbow.attach(_pinElbow);
6262
_gripper.attach(_pinGripper);
6363

64-
goDirectlyTo(0, 100, 50);
64+
//goDirectlyTo(0, 100, 50);
65+
goDirectlyToCylinder(0, 100, 50);
6566
openGripper();
6667
}
6768

@@ -92,6 +93,27 @@ void meArm::gotoPoint(float x, float y, float z) {
9293
delay(50);
9394
}
9495

96+
//Get x and y from theta and r
97+
void meArm::polarToCartesian(float theta, float r, float& x, float& y){
98+
_r = r;
99+
_t = theta;
100+
x = r*sin(theta);
101+
y = r*cos(theta);
102+
}
103+
104+
//Same as above but for cylindrical polar coodrinates
105+
void meArm::gotoPointCylinder(float theta, float r, float z){
106+
float x, y;
107+
polarToCartesian(theta, r, x, y);
108+
gotoPoint(x,y,z);
109+
}
110+
111+
void meArm::goDirectlyToCylinder(float theta, float r, float z){
112+
float x, y;
113+
polarToCartesian(theta, r, x, y);
114+
goDirectlyTo(x,y,z);
115+
}
116+
95117
//Check to see if possible
96118
bool meArm::isReachable(float x, float y, float z) {
97119
float radBase,radShoulder,radElbow;
@@ -121,3 +143,10 @@ float meArm::getZ() {
121143
return _z;
122144
}
123145

146+
147+
float meArm::getR() {
148+
return _r;
149+
}
150+
float meArm::getTheta() {
151+
return _t;
152+
}

meArm.h

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,11 @@ class meArm {
3636
void gotoPoint(float x, float y, float z);
3737
//Set servos to reach a certain point directly without caring how we get there
3838
void goDirectlyTo(float x, float y, float z);
39+
40+
//Same as above but for cylindrical polar coodrinates
41+
void gotoPointCylinder(float theta, float r, float z);
42+
void goDirectlyToCylinder(float theta, float r, float z);
43+
3944
//Grab something
4045
void openGripper();
4146
//Let go of something
@@ -46,8 +51,13 @@ class meArm {
4651
float getX();
4752
float getY();
4853
float getZ();
54+
55+
float getR();
56+
float getTheta();
4957
private:
58+
void polarToCartesian(float theta, float r, float& x, float& y);
5059
float _x, _y, _z;
60+
float _r, _t;
5161
Servo _base, _shoulder, _elbow, _gripper;
5262
ServoInfo _svoBase, _svoShoulder, _svoElbow, _svoGripper;
5363
int _pinBase, _pinShoulder, _pinElbow, _pinGripper;

0 commit comments

Comments
 (0)