| 6 |
6 |
|
| 7 |
7 |
int encoder_ltm1, encoder_rtm1;
|
| 8 |
8 |
|
|
9 |
//Measures mm displacement in x and y from starting position. (+x:theta=0 +y:theta=M_PI/2)
|
| 9 |
10 |
long diff_x,diff_y;
|
|
11 |
|
|
12 |
//Measures radian angle displacement from starting position. (initially 0)
|
| 10 |
13 |
double angle;
|
| 11 |
14 |
|
| 12 |
15 |
|
| ... | ... | |
| 41 |
44 |
}
|
| 42 |
45 |
|
| 43 |
46 |
void odometry_reset(void){
|
| 44 |
|
char buf[40];
|
| 45 |
47 |
diff_x = 0;
|
| 46 |
48 |
diff_y = 0;
|
| 47 |
49 |
encoder_ltm1 = encoder_read(LEFT);
|
| 48 |
50 |
encoder_rtm1 = encoder_read(RIGHT);
|
| 49 |
|
//sprintf(buf,"(en_right,en_left) in um: (%d,%d)\n\r",encoder_ltm1,encoder_rtm1);
|
| 50 |
|
//usb_puts(buf);
|
| 51 |
51 |
angle = 0.0;
|
| 52 |
52 |
}
|
| 53 |
53 |
|
| 54 |
|
/*Currently assumes robot only goes forward.
|
|
54 |
/*Currently assumes robot only goes forward (neither wheel goes backward).
|
| 55 |
55 |
void odometry_run(void){
|
| 56 |
56 |
double theta;
|
| 57 |
57 |
int encoder_left, encoder_right,dl,dr;
|
| ... | ... | |
| 76 |
76 |
|
| 77 |
77 |
if(dl == dr){
|
| 78 |
78 |
distance_um = dl*CLICK_DISTANCE_UM;
|
| 79 |
|
//sprintf(buf,"Distance in um: %ld\n\r",distance_um);
|
| 80 |
|
//usb_puts(buf);
|
| 81 |
79 |
diff_x += distance_um*cos(angle)/1000;
|
| 82 |
80 |
diff_y += distance_um*sin(angle)/1000;
|
|
81 |
//sprintf(buf,"Distance in um: %d\n\r",distance_um);
|
|
82 |
//usb_puts(buf);
|
| 83 |
83 |
return;
|
| 84 |
84 |
}
|
| 85 |
85 |
|
| ... | ... | |
| 87 |
87 |
turning_radius = ROBOT_WIDTH_UM * dl / (dr - dl); //um
|
| 88 |
88 |
theta = ((double)(dr-dl)*CLICK_DISTANCE_UM) / ((double)ROBOT_WIDTH_UM);
|
| 89 |
89 |
distance_um = theta*((double)(turning_radius + ROBOT_WIDTH_UM/2));
|
| 90 |
|
//sprintf(buf,"Distance in um: %d\n\r",distance_um);
|
| 91 |
|
//usb_puts(buf);
|
| 92 |
90 |
}
|
| 93 |
|
|
| 94 |
91 |
else{ //CW negative.
|
| 95 |
92 |
turning_radius = ROBOT_WIDTH_UM * dr / (dl - dr); //um
|
| 96 |
93 |
theta = -((double)(dl-dr)*CLICK_DISTANCE_UM) / ((double)ROBOT_WIDTH_UM);
|
| 97 |
94 |
distance_um = -theta*((double)(turning_radius + ROBOT_WIDTH_UM/2));
|
| 98 |
|
//sprintf(buf,"Distance in um: %d\n\r",distance_um);
|
| 99 |
|
//usb_puts(buf);
|
| 100 |
95 |
|
| 101 |
96 |
}
|
|
97 |
|
|
98 |
//sprintf(buf,"Distance in um: %d\n\r",distance_um);
|
|
99 |
//usb_puts(buf);
|
| 102 |
100 |
|
| 103 |
101 |
diff_x += distance_um * cos(angle)/1000;
|
| 104 |
102 |
diff_y += distance_um * sin(angle)/1000;
|
| ... | ... | |
| 109 |
107 |
encoder_rtm1 = encoder_right;
|
| 110 |
108 |
}*/
|
| 111 |
109 |
|
|
110 |
|
| 112 |
111 |
/*Generalized version of odometry.*/
|
| 113 |
112 |
void odometry_run(void){
|
| 114 |
113 |
//Angle swept through in a time step CCW-
|
| 115 |
114 |
double theta, rl, dc;
|
| 116 |
115 |
long dr,dl;
|
| 117 |
|
char buf[40];
|
| 118 |
116 |
|
| 119 |
117 |
//Get the change in wheel positions
|
| 120 |
118 |
{
|
| ... | ... | |
| 123 |
121 |
|
| 124 |
122 |
dl = encoder_left - encoder_ltm1;
|
| 125 |
123 |
dr = encoder_right - encoder_rtm1;
|
| 126 |
|
|
|
124 |
|
|
125 |
//No motion.
|
|
126 |
if(dl == 0 && dr == 0) return;
|
|
127 |
|
| 127 |
128 |
encoder_ltm1 = encoder_left;
|
| 128 |
129 |
encoder_rtm1 = encoder_right;
|
| 129 |
130 |
|
| ... | ... | |
| 137 |
138 |
dl *= CLICK_DISTANCE_UM; //um
|
| 138 |
139 |
dr *= CLICK_DISTANCE_UM;
|
| 139 |
140 |
}
|
|
141 |
|
| 140 |
142 |
|
| 141 |
143 |
if(dl == dr){
|
| 142 |
|
diff_x += dl*cos(angle)/1000;
|
| 143 |
|
diff_y += dl*sin(angle)/1000;
|
|
144 |
diff_x += lround(dl*cos(angle)/1000.0); //mm
|
|
145 |
diff_y += lround(dl*sin(angle)/1000.0); //mm
|
| 144 |
146 |
return;
|
| 145 |
147 |
}
|
| 146 |
148 |
|
| 147 |
149 |
//Call the left wheel 0, clockwise positive.
|
| 148 |
150 |
rl = ((double)(ROBOT_WIDTH_UM*dl))/((double)(dl - dr)); //um
|
| 149 |
|
theta = ((double)(dl - dr))/((double)ROBOT_WIDTH_UM); //rad
|
| 150 |
|
|
| 151 |
|
dc = (rl - ROBOT_WIDTH_UM/2)*theta; //um
|
|
151 |
theta = ((double)(dl - dr))/((double)ROBOT_WIDTH_UM); //rad
|
| 152 |
152 |
|
| 153 |
|
//Change state variables.
|
| 154 |
|
diff_x += ((dc * cos(angle))/1000); //mm
|
| 155 |
|
diff_y += ((dc * sin(angle))/1000); //mm
|
| 156 |
|
|
|
153 |
//Distance the center has traveled.
|
|
154 |
dc = lround( (theta * (rl - ROBOT_WIDTH_UM)) / 2.0 ); //um
|
|
155 |
|
| 157 |
156 |
//angle is necessarily CCW+, so subtract.
|
| 158 |
|
angle -= theta;
|
|
157 |
angle -= ANGLE_SCALE * theta;
|
| 159 |
158 |
|
|
159 |
//Change state variables.
|
|
160 |
diff_x += lround((DISTANCE_SCALE * dc * cos(angle))/1000.0); //mm
|
|
161 |
diff_y += lround((DISTANCE_SCALE * dc * sin(angle))/1000.0); //mm
|
| 160 |
162 |
}
|
| 161 |
163 |
|
| 162 |
164 |
ISR(TIMER2_COMP_vect){
|
| 163 |
165 |
odometry_run();
|
| 164 |
166 |
}
|
| 165 |
167 |
|
|
168 |
long lround(double d){
|
|
169 |
double f = floor(d);
|
|
170 |
return (long)(d - f > 0.5 ? f + 1 : f);
|
|
171 |
}
|
| 166 |
172 |
|
|
173 |
|