$search
00001 package edu.tum.cs.ias.knowrob.vis.items; 00002 00003 import java.io.BufferedReader; 00004 import java.io.FileNotFoundException; 00005 import java.io.FileReader; 00006 import java.io.IOException; 00007 import java.io.PrintStream; 00008 import java.util.*; 00009 00010 import edu.tum.cs.ias.knowrob.util.datastructures.Hashmap2List; 00011 import edu.tum.cs.ias.knowrob.util.datastructures.Vector3f; 00012 import edu.tum.cs.ias.knowrob.vis.Canvas; 00013 import edu.tum.cs.ias.knowrob.vis.Drawable; 00014 import edu.tum.cs.ias.knowrob.vis.DrawableAnimated; 00015 00021 public class Trajectory implements Drawable, DrawableAnimated { 00022 00023 public Vector<Point> points; 00024 public HashMap<Point,Set<Point>> mergeSet = new HashMap<Point,Set<Point>>(); 00025 public double minDistance = Double.MAX_VALUE; 00026 public float pointSize = 0.0f, sphereSize = 120.0f; 00027 public boolean pointsAsSpheres = true; 00028 public int pointColor = 0xffcbcbcb, sphereColor = 0x99ffff00; 00029 public float minx, miny, minz, maxx, maxy, maxz; 00030 public float range; 00031 public double minDis; 00032 public int lineColor = 0xffffffff; 00033 public AnimationMode animationMode = AnimationMode.BuildUp; 00034 public int minStep = 0; 00035 00036 public enum AnimationMode { BuildUp, AllAtOnce }; 00037 00038 protected Hashmap2List<Integer, Drawable> animationEffects; 00039 00040 public Trajectory() { 00041 animationEffects = new Hashmap2List<Integer, Drawable>(); 00042 points = new Vector<Point>(); 00043 resetStats(); 00044 } 00045 00046 protected void resetStats() { 00047 minx = Float.MAX_VALUE; miny = Float.MAX_VALUE; minz = Float.MAX_VALUE; 00048 maxx = Float.MIN_VALUE; maxy = Float.MIN_VALUE; maxz = Float.MIN_VALUE; 00049 range = 0; 00050 } 00051 00052 protected void updateStats(float x, float y, float z) { 00053 minx = Math.min(x, minx); 00054 miny = Math.min(y, miny); 00055 minz = Math.min(z, minz); 00056 maxx = Math.max(x, maxx); 00057 maxy = Math.max(y, maxy); 00058 maxz = Math.max(z, maxz); 00059 float xrange = maxx - minx; 00060 float yrange = maxy - miny; 00061 float zrange = maxz - minz; 00062 range = Math.max(Math.max(xrange, yrange), zrange); 00063 } 00064 00065 public void addPoint(float x, float y, float z) { 00066 points.add(new Point(x, y, z, pointColor, pointSize)); 00067 updateStats(x,y,z); 00068 } 00069 00070 public void setLabels(java.io.File ascFile) throws NumberFormatException, IOException { 00071 int[] colors = new int[] {0xffff0000, 0xff00ff00, 0xff0000ff, 0xffffff00, 0xffff00ff, 0xff00ffff, 0xffff8800, 0xffff0088, 0xff88ff00, 0xff00ff88, 0xff8800ff, 0xff0088ff}; 00072 BufferedReader r = new BufferedReader(new FileReader(ascFile)); 00073 String line; 00074 int iLine = 0; 00075 while((line = r.readLine()) != null) { 00076 int l = (int)Math.rint(Double.parseDouble(line)); 00077 this.points.get(iLine).color = colors[l]; 00078 iLine++; 00079 } 00080 } 00081 00082 public float getMaxAbsCoord() { 00083 float x = Math.max(Math.abs(minx), Math.abs(maxx)); 00084 float y = Math.max(Math.abs(miny), Math.abs(maxy)); 00085 float z = Math.max(Math.abs(minz), Math.abs(maxz)); 00086 float xy = Math.max(x, y); 00087 return Math.max(xy, z); 00088 } 00089 00090 public void draw(Canvas c, int step) { 00091 c.pushMatrix(); 00092 00093 pointSize = range / 150; 00094 sphereSize = pointSize * 2; 00095 //System.out.println(pointSize); 00096 Point prev = null; 00097 int s = 0; 00098 c.sphereDetail(3); 00099 for(Point p : points) { 00100 if(s > step && animationMode == AnimationMode.BuildUp) 00101 break; 00102 if(s++ < minStep) 00103 continue; 00104 if(p.size == 0.0f) 00105 p.size = pointSize; 00106 if(pointsAsSpheres) 00107 p.drawAsSphere(c); 00108 else 00109 p.draw(c); 00110 if(prev != null) { // draw line connecting previous point with current point 00111 //c.stroke(255,255,255); 00112 //System.out.printf("%f %f %f -> %f %f %f\n",prev.x, prev.y, prev.z, p.x, p.y, p.z); 00113 //c.line(prev.v.x, prev.v.y, prev.v.z, p.v.x, p.v.y, p.v.z); 00114 c.drawLine(prev.v, p.v, lineColor); 00115 } 00116 prev = p; 00117 } 00118 c.sphereDetail(30); 00119 00120 // stuff for current pos 00121 if(step < points.size()) { 00122 Point currentPos = points.get(step); 00123 00124 // draw sphere around it 00125 new Sphere(currentPos.v.x, currentPos.v.y, currentPos.v.z, sphereSize, sphereColor).draw(c); 00126 00127 // draw animation effects if any 00128 Vector<Drawable> effects = animationEffects.get(step); 00129 if(effects != null) { 00130 System.out.println("drawing effects for step " + step); 00131 for(Drawable d : effects) 00132 d.draw(c); 00133 } 00134 00135 // focus eye on it 00136 c.setEyeTarget(currentPos.v); 00137 } 00138 00139 c.popMatrix(); 00140 } 00141 00142 public int getNumSteps() { 00143 return points.size(); 00144 } 00145 00146 public void draw(Canvas c) { 00147 draw(c, this.getMaxStep()); 00148 } 00149 00155 public void saveAsc(java.io.File f) throws FileNotFoundException { 00156 PrintStream s = new PrintStream(f); 00157 for(Point p : this.points) { 00158 s.print(p.v.x); 00159 s.print(' '); 00160 s.print(p.v.y); 00161 s.print(' '); 00162 s.print(p.v.z); 00163 s.print('\n'); 00164 } 00165 } 00166 00167 public void readAsc(java.io.File matlabAsciiFile) throws NumberFormatException, IOException { 00168 readAsc(matlabAsciiFile, 0); 00169 } 00170 00177 public void readAsc(java.io.File matlabAsciiFile, int startLine) throws NumberFormatException, IOException { 00178 BufferedReader r = new BufferedReader(new FileReader(matlabAsciiFile)); 00179 String line; 00180 int iLine = 0; 00181 while((line = r.readLine()) != null) { 00182 if(iLine++ < startLine) 00183 continue; 00184 String[] parts = line.trim().split("\\s+"); 00185 float x = Float.parseFloat(parts[0]); 00186 float y = Float.parseFloat(parts[1]); 00187 float z; 00188 if(parts.length == 3) 00189 z = Float.parseFloat(parts[2]); 00190 else 00191 z = 0; 00192 this.addPoint(x, y, z); 00193 } 00194 } 00195 00196 public double getMinDistance(){ 00197 // minimum distance between two adjacent points 00198 double distance = 0; 00199 int i = 0; 00200 for (Point p: points){ 00201 if(i >0){ 00202 distance = p.v.distance(points.get(i-1).v); 00203 if (distance < minDistance) 00204 minDistance = distance; 00205 } 00206 i++; 00207 } 00208 return minDistance; 00209 } 00210 00211 public void merge(Point p1, Point p2){ 00212 Set<Point> s1 = mergeSet.get(p1); 00213 Set<Point> s2 = mergeSet.get(p2); 00214 Set<Point> s; 00215 if(s1 != null && s2 != null){ 00216 s1.addAll(s2); 00217 for(Point p : s2){ 00218 mergeSet.put(p,s1); 00219 } 00220 s = s1; 00221 } 00222 else { 00223 if(s1 != null){ 00224 s = s1; 00225 } 00226 if(s2 != null){ 00227 s = s2; 00228 } 00229 else{ 00230 s = new HashSet<Point>(); 00231 } 00232 } 00233 s.add(p1); 00234 s.add(p2); 00235 mergeSet.put(p1,s); 00236 mergeSet.put(p2,s); 00237 } 00238 00242 public void mergePoints() { 00243 System.out.println("Merging points..."); 00244 float proximity_threshold = range/50; 00245 float direction_threshold = 60; // in degrees 00246 00247 int i = 0; 00248 java.util.PriorityQueue<Double> min_distances = new PriorityQueue<Double>(); 00249 for(Point p : points) { 00250 if(i >= 3) { 00251 // check previous points for proximity 00252 double min_distance = Double.MAX_VALUE; 00253 int min_distance_point_idx = -1; 00254 for(int j = i-3; j >= 0; j--) { 00255 Point p2 = points.get(j); 00256 double dist = p.v.distance(p2.v); 00257 if(dist != 0.0 && dist < min_distance) { 00258 min_distance = dist; 00259 min_distance_point_idx = j; 00260 } 00261 } 00262 min_distances.add(min_distance); 00263 00264 // merge if distance to closest previous point is small enough 00265 if(min_distance < proximity_threshold) { 00266 Point p2 = points.get(min_distance_point_idx); 00267 00268 // ... and directions are similar 00269 boolean dirSimilar = false; 00270 if(min_distance_point_idx == 0) 00271 dirSimilar = true; 00272 else { 00273 Vector3f dir1 = new Vector3f(p.v); 00274 dir1.sub(points.get(i-1).v); 00275 Vector3f dir2 = new Vector3f(p2.v); 00276 dir2.sub(points.get(min_distance_point_idx-1).v); 00277 double angle = dir1.angle(dir2); 00278 //System.out.println("angle = " + angle * 180/Math.PI); 00279 dirSimilar = angle < Math.PI*direction_threshold/180; 00280 } 00281 00282 if(dirSimilar) { // merge p and p2 00283 // animation events 00284 PointPair pp = new PointPair(new Point(p.v, 0xffff00ff, pointSize), new Point(p2.v, 0xffff00ff, pointSize), 0xffff0000); 00285 animationEffects.put(i, pp); 00286 animationEffects.put(min_distance_point_idx, pp); 00287 00288 // actual merge 00289 // any point that is equal to point p or p2 is merged 00290 merge(p,p2); 00291 Vector3f newPos = new Vector3f((p.v.x+p2.v.x) / 2, (p.v.y+p2.v.y) / 2, (p.v.z+p2.v.z) / 2); 00292 for (Point p3 : points){ 00293 if(p3.v.distance(p.v) == 0 || p3.v.distance(p2.v) == 0){ 00294 p3.v = newPos; 00295 p3.color = 0xffff0000; 00296 merge(p,p3); 00297 } 00298 } 00299 00300 } 00301 } 00302 } 00303 00304 i++; 00305 } 00306 00307 // print minimum distances 00308 Double prev_d = null; 00309 double max_diff = Double.MIN_VALUE; 00310 double max_diff_value = 0; 00311 while(!min_distances.isEmpty()) { 00312 double d = min_distances.remove(); 00313 if(prev_d != null) { 00314 double diff = d-prev_d; 00315 if(diff > max_diff) { 00316 max_diff = diff; 00317 max_diff_value = d; 00318 } 00319 } 00320 prev_d = d; 00321 //System.out.println(d); 00322 } 00323 System.out.println("max diff: " + max_diff + " @ " + max_diff_value); 00324 00325 } 00329 public void mergeLines(){ 00330 System.out.println("Merging lines..."); 00331 double thresh = range/30.0; 00332 double dirthresh = 60; 00333 System.out.println(thresh); 00334 //how many points should be considered 00335 int fut = 2; 00336 int past = 2; 00337 for(int k = 0; k < 20; k++){ 00338 HashSet<Set<Point>> setOfSets = new HashSet<Set<Point>>(mergeSet.values()); 00339 for(Set<Point> s : setOfSets){ 00340 HashSet<Point> curSet = new HashSet<Point>(s); 00341 for(Point p1 : s){ 00342 curSet.remove(p1); 00343 // merge Points that have the same distance from starting 00344 // point and that are already close to each other 00345 for(Point p2 : curSet){ 00346 for (int l = 1; l <= fut; l++){ 00347 if(points.indexOf(p1)+l < points.size() && points.indexOf(p2)+l < points.size()){ 00348 Point p1Post1 = points.get(points.indexOf(p1)+l); 00349 Point p2Post1 = points.get(points.indexOf(p2)+l); 00350 Vector3f dir11 = new Vector3f(p1Post1.v); 00351 dir11.sub(p1.v); 00352 Vector3f dir21 = new Vector3f(p2Post1.v); 00353 dir21.sub(p2.v); 00354 double angle11 = dir11.angle(dir21); 00355 if (angle11 < dirthresh*Math.PI/180 && p1Post1.v.distance(p2Post1.v) < thresh){ 00356 // actual merge 00357 //merge(p1Post1,p2Post1); 00358 Vector3f newPos = new Vector3f((p1Post1.v.x+p2Post1.v.x) / 2, (p1Post1.v.y+p2Post1.v.y) / 2, (p1Post1.v.z+p2Post1.v.z) / 2); 00359 for(Point p : points){ 00360 if (p.v.distance(p1Post1.v) == 0 || p.v.distance(p2Post1.v) == 0){ 00361 p.v = newPos; 00362 p.color = 0xffff0000; 00363 } 00364 } 00365 } 00366 } 00367 } 00368 // same for prior points 00369 for (int l = 1; l <= past; l++){ 00370 if(points.indexOf(p1)-l > 0 && points.indexOf(p2)-l > 0){ 00371 Point p1Post1 = points.get(points.indexOf(p1)-l); 00372 Point p2Post1 = points.get(points.indexOf(p2)-l); 00373 Vector3f dir11 = new Vector3f(p1Post1.v); 00374 dir11.sub(p1.v); 00375 Vector3f dir21 = new Vector3f(p2Post1.v); 00376 dir21.sub(p2.v); 00377 double angle11 = dir11.angle(dir21); 00378 if (angle11 < dirthresh*Math.PI/180 && p1Post1.v.distance(p2Post1.v) < thresh){ 00379 // actual merge 00380 //merge(p1Post1, p2Post1); 00381 Vector3f newPos = new Vector3f((p1Post1.v.x+p2Post1.v.x) / 2, (p1Post1.v.y+p2Post1.v.y) / 2, (p1Post1.v.z+p2Post1.v.z) / 2); 00382 p1Post1.v = newPos; 00383 p2Post1.v = newPos; 00384 p1Post1.color = 0xffff0000; 00385 p2Post1.color = 0xffff0000; 00386 } 00387 } 00388 } 00389 } 00390 } 00391 } 00392 updateMerge(); 00393 } 00394 } 00395 00399 public void updateMerge(){ 00400 int i = 0; 00401 for(Point p : points){ 00402 for(int j = i+1; j < points.size(); j++){ 00403 if (p.v.distance(points.get(j).v) == 0) 00404 merge(p,points.get(j)); 00405 } 00406 i++; 00407 } 00408 } 00409 00413 public void smoothLines(){ 00414 int i = 0; 00415 for(Point p : points){ 00416 Vector<Point> succ = new Vector<Point>(); 00417 Vector<Point> line = new Vector<Point>(); 00418 for(int j = i+2; j < points.size(); j++){ 00419 Point pEnd = points.get(j); 00420 Vector3f dir = new Vector3f(pEnd.v); 00421 dir.sub(p.v); 00422 double dist = 0.0; 00423 line.clear(); 00424 for(int k = i+1; k < j; k++){ 00425 Point p2 = points.get(k); 00426 double a = dir.x*p2.v.x + dir.y*p2.v.y + dir.z*p2.v.z; 00427 double lambda = (a - (dir.x*p.v.x + dir.y*p.v.y + dir.z*p.v.z))/(dir.x*dir.x + dir.y*dir.y + dir.z*dir.z); 00428 Point l = new Point(p); 00429 l.v.x += lambda * dir.x; 00430 l.v.y += lambda * dir.y; 00431 l.v.z += lambda * dir.z; 00432 line.addElement(l); 00433 dist += l.v.distance(p2.v); 00434 } 00435 if (dist / (j-i) < 200){ 00436 succ = line; 00437 } 00438 else { 00439 if(j - i > 5){ 00440 System.out.println("Smoothing line"); 00441 //System.out.println("Size of succ: "+ succ.size()); 00442 int n = 0; 00443 for(int k = i+1; k < j-1; k++){ 00444 points.get(k).v = succ.get(n).v; 00445 points.get(k).color = 0xffff0000; 00446 n++; 00447 } 00448 i = j; 00449 } 00450 else 00451 i++; 00452 break; 00453 } 00454 } 00455 } 00456 } 00457 00458 public void findOscillations(){ 00459 int i = 0; 00460 int j = 0; 00461 double thresh = range/50.0; 00462 //double thresh = 150; 00463 System.out.println(thresh); 00464 int num = 0; 00465 int minnum = 5; 00466 Vector<Point> vec = new Vector<Point>(); 00467 for(Point p : points){ 00468 if(i>1){ 00469 num = 0; 00470 j = i; 00471 vec.clear(); 00472 // appends very close preceding points 00473 while(j > 0 && p.v.distance(points.get(j).v) < thresh){ 00474 vec.add(points.get(j)); 00475 j--; 00476 num++; 00477 } 00478 if(num > minnum){ 00479 // visualize oscillations and actual merge 00480 Point medPoint = new Point(0,0,0,pointColor,pointSize); 00481 for(Point medP : vec){ 00482 medPoint.v.add(medP.v); 00483 } 00484 medPoint.v.scale(1/(float)num); 00485 float medSize = (float)Math.log(num) * range/150; 00486 for(Point oscP : vec){ 00487 if (oscP != vec.get(0)) 00488 merge(oscP,vec.get(0)); 00489 oscP.copyPos(medPoint); 00490 oscP.color = 0xff0000ff; 00491 oscP.size = medSize; 00492 } 00493 } 00494 } 00495 i++; 00496 } 00497 } 00498 00502 public void center() { 00503 // determine mean point 00504 float x = 0, y = 0, z = 0; 00505 for(Point p : points) { 00506 x += p.v.x; 00507 y += p.v.y; 00508 z += p.v.z; 00509 } 00510 x /= points.size(); 00511 y /= points.size(); 00512 z /= points.size(); 00513 Vector3f mean = new Vector3f(x, y, z); 00514 // subtract mean from all points and update stats 00515 resetStats(); 00516 for(Point p : points) { 00517 p.v.sub(mean); 00518 updateStats(p.v.x, p.v.y, p.v.z); 00519 } 00520 } 00525 public void mergeRepeats(){ 00526 int i = 0; 00527 for(Point p : points){ 00528 int j = 1; 00529 int num = 0; 00530 while(i+j < points.size() && num < 3){ 00531 Point p2 = points.get(i+j); 00532 Point prep2 = points.get(i+j-1); 00533 if(p2.v.distance(prep2.v) > 0.1){ 00534 num++; 00535 if (p2.v.distance(p.v) < 0.1){ 00536 merge(p,prep2); 00537 Vector3f newPos = new Vector3f((p.v.x+prep2.v.x) / 2, (p.v.y+prep2.v.y) / 2, (p.v.z+prep2.v.z) / 2); 00538 for (Point p3 : points){ 00539 if(p3.v.distance(p.v) == 0 || p3.v.distance(prep2.v) == 0){ 00540 p3.v = newPos; 00541 p3.color = 0xffff0000; 00542 } 00543 } 00544 } 00545 } 00546 j++; 00547 } 00548 i++; 00549 } 00550 } 00551 00552 public void getTransitionPoints(){ 00553 double threshDist = 0.0f; 00554 double threshAngle = Math.PI * 00/180; 00555 HashSet<Set<Point>> setOfSets = new HashSet<Set<Point>>(mergeSet.values()); 00556 for(Set<Point> s : setOfSets){ 00557 HashSet<Point> curSet = new HashSet<Point>(s); 00558 for(Point p1 : s){ 00559 curSet.remove(p1); 00560 for(Point p2 : curSet){ 00561 // the first part is for searching forwards 00562 if(points.indexOf(p1)+1 < points.size() && points.indexOf(p2)+1 < points.size()){ 00563 Point succP1 = points.get(points.indexOf(p1)+1); 00564 Point succP2 = points.get(points.indexOf(p2)+1); 00565 // look only for real successor not merged points 00566 if(p1.v.distance(succP1.v) != 0 && p2.v.distance(succP2.v) != 0){ 00567 Vector3f dir1 = new Vector3f(p1.v); 00568 dir1.sub(succP1.v); 00569 Vector3f dir2 = new Vector3f(p2.v); 00570 dir2.sub(succP2.v); 00571 double angle = dir1.angle(dir2); 00572 // check for distance and angle threshold 00573 if (succP1.v.distance(succP2.v) > threshDist && angle >= threshAngle){ 00574 // check, whether the direction of the trajectory is the same! 00575 int k = 1; 00576 Point pre1 = new Point(p1); 00577 Point pre2 = new Point(p2); 00578 while(points.indexOf(p1)-k > 0){ 00579 pre1 = points.get(points.indexOf(p1)-k); 00580 if (pre1.v.distance(p1.v) > 0.1){ 00581 k = 1; 00582 break; 00583 } 00584 else 00585 k++; 00586 } 00587 while(points.indexOf(p2)-k > 0){ 00588 pre2 = points.get(points.indexOf(p2)-k); 00589 if (pre2.v.distance(p2.v) > 0.1){ 00590 break; 00591 } 00592 else 00593 k++; 00594 } 00595 if(pre1.v.distance(pre2.v) > 0.1) 00596 continue; 00597 // however: we do not want to find 'fake' transition points in lines 00598 // where there was just a 'oversight' by the merging algorithm, 00599 // therefore we look whether the trajectories meet again soon 00600 int l = 1; 00601 int fut1 = 0; 00602 int fut2 = 0; 00603 Set<Point> succ1 = new HashSet<Point>(); 00604 Set<Point> succ2 = new HashSet<Point>(); 00605 while(points.indexOf(p1)+l < points.size() && points.indexOf(p2)+l < points.size()){ 00606 if(fut1 < 4){ 00607 Point p11 = points.get(points.indexOf(p1)+l); 00608 Point p12 = points.get(points.indexOf(p1)+l-1); 00609 succ1.add(p11); 00610 if(p11.v.distance(p12.v) >= range/200 && !mergeSet.get(p1).contains(p11)){ 00611 fut1++; 00612 } 00613 } 00614 if(fut2 < 4){ 00615 Point p21 = points.get(points.indexOf(p2)+l); 00616 Point p22 = points.get(points.indexOf(p2)+l-1); 00617 succ2.add(p21); 00618 if(p21.v.distance(p22.v) >= range/200 && !mergeSet.get(p1).contains(p21)){ 00619 fut2++; 00620 } 00621 } 00622 l++; 00623 } 00624 boolean realTransition = true; 00625 for(Point pSucc1 : succ1){ 00626 for(Point pSucc2 : succ2){ 00627 if(pSucc1.v.distance(pSucc2.v) <= range/200) 00628 realTransition = false; 00629 } 00630 } 00631 if(realTransition){ 00632 System.out.println(">>>>>>> Got a transition point"); 00633 p1.size = range/75; 00634 p1.color = 0xff00ff00; 00635 } 00636 } 00637 } 00638 } 00639 // Same for the past! 00640 if(points.indexOf(p1)-1 > 0 && points.indexOf(p2)-1 > 0){ 00641 Point preP1 = points.get(points.indexOf(p1)-1); 00642 Point preP2 = points.get(points.indexOf(p2)-1); 00643 // look only for real predecessor not merged points 00644 if(p1.v.distance(preP1.v) != 0 && p2.v.distance(preP2.v) != 0){ 00645 Vector3f dir1 = new Vector3f(p1.v); 00646 dir1.sub(preP1.v); 00647 Vector3f dir2 = new Vector3f(p2.v); 00648 dir2.sub(preP2.v); 00649 double angle = dir1.angle(dir2); 00650 // check for distance and angle threshold 00651 if (preP1.v.distance(preP2.v) > threshDist && angle >= threshAngle){ 00652 // check, whether the direction of the trajectory is the same! 00653 int k = 1; 00654 Point succ1 = new Point(p1); 00655 Point succ2 = new Point(p2); 00656 while(points.indexOf(p1)+k < points.size()){ 00657 succ1 = points.get(points.indexOf(p1)+k); 00658 if (succ1.v.distance(p1.v) > 0.1){ 00659 k = 1; 00660 break; 00661 } 00662 else 00663 k++; 00664 } 00665 while(points.indexOf(p2)+k < points.size()){ 00666 succ2 = points.get(points.indexOf(p2)+k); 00667 if (succ2.v.distance(p2.v) > 0.1){ 00668 break; 00669 } 00670 else 00671 k++; 00672 } 00673 if(succ1.v.distance(succ2.v) > 0.1) 00674 continue; 00675 int l = 1; 00676 int fut1 = 0; 00677 int fut2 = 0; 00678 Set<Point> prec1 = new HashSet<Point>(); 00679 Set<Point> prec2 = new HashSet<Point>(); 00680 while(points.indexOf(p1)-l > 0 && points.indexOf(p2)-l > 0){ 00681 if(fut1 < 4){ 00682 Point p11 = points.get(points.indexOf(p1)-l); 00683 Point p12 = points.get(points.indexOf(p1)-l+1); 00684 prec1.add(p11); 00685 if(p11.v.distance(p12.v) >= range/200 && !mergeSet.get(p1).contains(p11)){ 00686 fut1++; 00687 } 00688 } 00689 if(fut2 < 4){ 00690 Point p21 = points.get(points.indexOf(p2)-l); 00691 Point p22 = points.get(points.indexOf(p2)-l+1); 00692 prec2.add(p21); 00693 if(p21.v.distance(p22.v) >= range/200 && !mergeSet.get(p1).contains(p21)){ 00694 fut2++; 00695 } 00696 } 00697 l++; 00698 } 00699 boolean realTransition = true; 00700 for(Point pSucc1 : prec1){ 00701 for(Point pSucc2 : prec2){ 00702 if(pSucc1.v.distance(pSucc2.v) <= range/200) 00703 realTransition = false; 00704 } 00705 } 00706 if(realTransition){ 00707 System.out.println(">>>>>>> Got a transition point"); 00708 p1.size = range/75; 00709 p1.color = 0xff00ff00; 00710 } 00711 } 00712 } 00713 } 00714 } 00715 } 00716 } 00717 } 00718 00719 public int getMaxStep() { 00720 return getNumSteps()-1; 00721 } 00722 00723 public class PointPair implements Drawable { 00724 00725 protected Point p1, p2; 00726 protected int linecolor; 00727 00728 public PointPair(Point p1, Point p2, int linecolor) { 00729 this.p1 = p2; 00730 this.p2 = p2; 00731 this.linecolor = linecolor; 00732 } 00733 00734 public void draw(Canvas c) { 00735 p1.size = pointSize; 00736 p2.size = pointSize; 00737 p1.draw(c); 00738 p2.draw(c); 00739 c.drawLine(p1.v, p2.v, linecolor); 00740 } 00741 } 00742 }