Trajectory.java
Go to the documentation of this file.
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                 s.close();
00166         }
00167         
00168         public void readAsc(java.io.File matlabAsciiFile) throws NumberFormatException, IOException {
00169                 readAsc(matlabAsciiFile, 0);
00170         }
00171         
00178         public void readAsc(java.io.File matlabAsciiFile, int startLine) throws NumberFormatException, IOException {
00179                 BufferedReader r = new BufferedReader(new FileReader(matlabAsciiFile));
00180                 String line;
00181                 int iLine = 0;
00182                 while((line = r.readLine()) != null) {
00183                         if(iLine++ < startLine)
00184                                 continue;
00185                         String[] parts = line.trim().split("\\s+");
00186                         float x = Float.parseFloat(parts[0]);
00187                         float y = Float.parseFloat(parts[1]);
00188                         float z;
00189                         if(parts.length == 3)
00190                                 z = Float.parseFloat(parts[2]);
00191                         else 
00192                                 z = 0;
00193                         this.addPoint(x, y, z);
00194                 }
00195                 r.close();
00196         }
00197         
00198         public double getMinDistance(){
00199                 // minimum distance between two adjacent points
00200                 double distance = 0;
00201                 int i = 0;
00202                 for (Point p: points){
00203                         if(i >0){
00204                                 distance = p.v.distance(points.get(i-1).v);
00205                                 if (distance < minDistance)
00206                                         minDistance = distance;
00207                         }
00208                         i++;
00209                 }
00210                 return minDistance;
00211         }
00212         
00213         public void merge(Point p1, Point p2){
00214                 Set<Point> s1 = mergeSet.get(p1);
00215                 Set<Point> s2 = mergeSet.get(p2);
00216                 Set<Point> s;
00217                 if(s1 != null && s2 != null){
00218                         s1.addAll(s2);
00219                         for(Point p : s2){
00220                                 mergeSet.put(p,s1);
00221                         }
00222                         s = s1;
00223                 }
00224                 else {
00225                         if(s1 != null){
00226                                 s = s1;
00227                         }
00228                         if(s2 != null){
00229                                 s = s2;
00230                         }
00231                         else{
00232                                 s = new HashSet<Point>();
00233                         }
00234                 }
00235                 s.add(p1);
00236                 s.add(p2);
00237                 mergeSet.put(p1,s);
00238                 mergeSet.put(p2,s);
00239         }
00240 
00244         public void mergePoints() {
00245                 System.out.println("Merging points...");
00246                 float proximity_threshold = range/50;           
00247                 float direction_threshold = 60; // in degrees
00248                 
00249                 int i = 0;
00250                 java.util.PriorityQueue<Double> min_distances = new PriorityQueue<Double>();
00251                 for(Point p : points) {
00252                         if(i >= 3) {            
00253                                 // check previous points for proximity
00254                                 double min_distance = Double.MAX_VALUE;
00255                                 int min_distance_point_idx = -1;
00256                                 for(int j = i-3; j >= 0; j--) {
00257                                         Point p2 = points.get(j);
00258                                         double dist = p.v.distance(p2.v);
00259                                         if(dist != 0.0 && dist < min_distance) {
00260                                                 min_distance = dist;
00261                                                 min_distance_point_idx = j;
00262                                         }
00263                                 }
00264                                 min_distances.add(min_distance);
00265                                 
00266                                 // merge if distance to closest previous point is small enough
00267                                 if(min_distance < proximity_threshold) {
00268                                         Point p2 = points.get(min_distance_point_idx);
00269                                         
00270                                         // ... and directions are similar
00271                                         boolean dirSimilar = false;
00272                                         if(min_distance_point_idx == 0)
00273                                                 dirSimilar = true;
00274                                         else {
00275                                                 Vector3f dir1 = new Vector3f(p.v);
00276                                                 dir1.sub(points.get(i-1).v);
00277                                                 Vector3f dir2 = new Vector3f(p2.v);
00278                                                 dir2.sub(points.get(min_distance_point_idx-1).v);
00279                                                 double angle = dir1.angle(dir2);
00280                                                 //System.out.println("angle = " + angle * 180/Math.PI);
00281                                                 dirSimilar = angle < Math.PI*direction_threshold/180;
00282                                         }
00283                                         
00284                                         if(dirSimilar) { // merge p and p2
00285                                                 // animation events
00286                                                 PointPair pp = new PointPair(new Point(p.v, 0xffff00ff, pointSize), new Point(p2.v, 0xffff00ff, pointSize), 0xffff0000);
00287                                                 animationEffects.put(i, pp);
00288                                                 animationEffects.put(min_distance_point_idx, pp);
00289                                                 
00290                                                 // actual merge
00291                                                 // any point that is equal to point p or p2 is merged
00292                                                 merge(p,p2);
00293                                                 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);
00294                                                 for (Point p3 : points){
00295                                                         if(p3.v.distance(p.v) == 0 || p3.v.distance(p2.v) == 0){
00296                                                                 p3.v = newPos;
00297                                                                 p3.color = 0xffff0000;
00298                                                                 merge(p,p3);
00299                                                         }
00300                                                 }
00301                                                 
00302                                         }
00303                                 }                                       
00304                         }
00305                         
00306                         i++;
00307                 }
00308                 
00309                 // print minimum distances
00310                 Double prev_d = null;
00311                 double max_diff = Double.MIN_VALUE;
00312                 double max_diff_value = 0;
00313                 while(!min_distances.isEmpty()) {
00314                         double d = min_distances.remove();
00315                         if(prev_d != null) {
00316                                 double diff = d-prev_d;
00317                                 if(diff > max_diff) {
00318                                         max_diff = diff;
00319                                         max_diff_value = d;
00320                                 }
00321                         }
00322                         prev_d = d;
00323                         //System.out.println(d);
00324                 }
00325                 System.out.println("max diff: " + max_diff + " @ " + max_diff_value);
00326                 
00327         }
00331         public void mergeLines(){
00332                 System.out.println("Merging lines...");
00333                 double thresh = range/30.0;
00334                 double dirthresh = 60;
00335                 System.out.println(thresh);
00336                 //how many points should be considered
00337                 int fut = 2;
00338                 int past = 2;
00339                 for(int k = 0; k < 20; k++){
00340                         HashSet<Set<Point>> setOfSets = new HashSet<Set<Point>>(mergeSet.values());
00341                         for(Set<Point> s : setOfSets){
00342                                 HashSet<Point> curSet = new HashSet<Point>(s);
00343                                 for(Point p1 : s){
00344                                         curSet.remove(p1);
00345                                         // merge Points that have the same distance from starting
00346                                         // point and that are already close to each other
00347                                         for(Point p2 : curSet){
00348                                                 for (int l = 1; l <= fut; l++){
00349                                                         if(points.indexOf(p1)+l < points.size() && points.indexOf(p2)+l < points.size()){
00350                                                                 Point p1Post1 = points.get(points.indexOf(p1)+l);
00351                                                                 Point p2Post1 = points.get(points.indexOf(p2)+l);
00352                                                                 Vector3f dir11 = new Vector3f(p1Post1.v);
00353                                                                 dir11.sub(p1.v);
00354                                                                 Vector3f dir21 = new Vector3f(p2Post1.v);
00355                                                                 dir21.sub(p2.v);
00356                                                                 double angle11 = dir11.angle(dir21);
00357                                                                 if (angle11 < dirthresh*Math.PI/180 && p1Post1.v.distance(p2Post1.v) < thresh){
00358                                                                         // actual merge
00359                                                                         //merge(p1Post1,p2Post1);
00360                                                                         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);
00361                                                                         for(Point p : points){
00362                                                                                 if (p.v.distance(p1Post1.v) == 0 || p.v.distance(p2Post1.v) == 0){
00363                                                                                         p.v = newPos;
00364                                                                                         p.color = 0xffff0000;
00365                                                                                 }
00366                                                                         }
00367                                                                 }
00368                                                         }
00369                                                 }
00370                                                 // same for prior points                                                
00371                                                 for (int l = 1; l <= past; l++){
00372                                                         if(points.indexOf(p1)-l > 0 && points.indexOf(p2)-l > 0){
00373                                                                 Point p1Post1 = points.get(points.indexOf(p1)-l);
00374                                                                 Point p2Post1 = points.get(points.indexOf(p2)-l);
00375                                                                 Vector3f dir11 = new Vector3f(p1Post1.v);
00376                                                                 dir11.sub(p1.v);
00377                                                                 Vector3f dir21 = new Vector3f(p2Post1.v);
00378                                                                 dir21.sub(p2.v);
00379                                                                 double angle11 = dir11.angle(dir21);
00380                                                                 if (angle11 < dirthresh*Math.PI/180 && p1Post1.v.distance(p2Post1.v) < thresh){
00381                                                                 // actual merge
00382                                                                 //merge(p1Post1, p2Post1);
00383                                                                 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);
00384                                                                 p1Post1.v = newPos;
00385                                                                 p2Post1.v = newPos;
00386                                                                 p1Post1.color = 0xffff0000;
00387                                                                 p2Post1.color = 0xffff0000;
00388                                                                 }
00389                                                         }
00390                                                 }
00391                                         }
00392                                 }
00393                         }
00394                         updateMerge();
00395                 }
00396         }
00397         
00401         public void updateMerge(){
00402                 int i = 0;
00403                 for(Point p : points){
00404                         for(int j = i+1; j < points.size(); j++){
00405                                 if (p.v.distance(points.get(j).v) == 0)
00406                                         merge(p,points.get(j));
00407                         }
00408                         i++;
00409                 }
00410         }
00411         
00415         public void smoothLines(){
00416                 int i = 0;
00417                 for(Point p : points){
00418                         Vector<Point> succ = new Vector<Point>();
00419                         Vector<Point> line = new Vector<Point>();
00420                         for(int j = i+2; j < points.size(); j++){
00421                                 Point pEnd = points.get(j);
00422                                 Vector3f dir = new Vector3f(pEnd.v);
00423                                 dir.sub(p.v);
00424                                 double dist = 0.0;
00425                                 line.clear();
00426                                 for(int k = i+1; k < j; k++){
00427                                         Point p2 = points.get(k);
00428                                         double a = dir.x*p2.v.x + dir.y*p2.v.y + dir.z*p2.v.z;
00429                                         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);
00430                                         Point l = new Point(p);
00431                                         l.v.x += lambda * dir.x;
00432                                         l.v.y += lambda * dir.y;
00433                                         l.v.z += lambda * dir.z;
00434                                         line.addElement(l);
00435                                         dist += l.v.distance(p2.v);
00436                                 }
00437                                 if (dist / (j-i) < 200){
00438                                         succ = line;
00439                                 }
00440                                 else {
00441                                         if(j - i > 5){
00442                                                 System.out.println("Smoothing line");
00443                                                 //System.out.println("Size of succ: "+ succ.size());
00444                                                 int n = 0;
00445                                                 for(int k = i+1; k < j-1; k++){
00446                                                         points.get(k).v = succ.get(n).v;
00447                                                         points.get(k).color = 0xffff0000;
00448                                                         n++;
00449                                                 }
00450                                                 i = j;
00451                                         }
00452                                         else
00453                                                 i++;
00454                                         break;
00455                                 }
00456                         }
00457                 }
00458         }
00459         
00460         public void findOscillations(){
00461                 int i = 0;
00462                 int j = 0;
00463                 double thresh = range/50.0;
00464                 //double thresh = 150;
00465                 System.out.println(thresh);
00466                 int num = 0;
00467                 int minnum = 5;
00468                 Vector<Point> vec = new Vector<Point>();
00469                 for(Point p : points){
00470                         if(i>1){
00471                                 num = 0;
00472                                 j = i;
00473                                 vec.clear();
00474                                 // appends very close preceding points
00475                                 while(j > 0 && p.v.distance(points.get(j).v) < thresh){
00476                                         vec.add(points.get(j));
00477                                         j--;
00478                                         num++;
00479                                 }
00480                                 if(num > minnum){
00481                                         // visualize oscillations and actual merge
00482                                         Point medPoint = new Point(0,0,0,pointColor,pointSize); 
00483                                         for(Point medP : vec){
00484                                                 medPoint.v.add(medP.v);
00485                                         }
00486                                         medPoint.v.scale(1/(float)num);
00487                                         float medSize = (float)Math.log(num) * range/150;
00488                                         for(Point oscP : vec){
00489                                                 if (oscP != vec.get(0))
00490                                                         merge(oscP,vec.get(0));
00491                                                 oscP.copyPos(medPoint);
00492                                                 oscP.color = 0xff0000ff;
00493                                                 oscP.size = medSize;
00494                                         }
00495                                 }
00496                         }
00497                         i++;
00498                 }
00499         }
00500         
00504         public void center() {
00505                 // determine mean point
00506                 float x = 0, y = 0, z = 0;
00507                 for(Point p : points) {
00508                         x += p.v.x;
00509                         y += p.v.y;
00510                         z += p.v.z;
00511                 }
00512                 x /= points.size();
00513                 y /= points.size();
00514                 z /= points.size();
00515                 Vector3f mean = new Vector3f(x, y, z);
00516                 // subtract mean from all points and update stats
00517                 resetStats();
00518                 for(Point p : points) { 
00519                         p.v.sub(mean);
00520                         updateStats(p.v.x, p.v.y, p.v.z);
00521                 }
00522         }
00527         public void mergeRepeats(){
00528                 int i = 0;
00529                 for(Point p : points){
00530                         int j = 1;
00531                         int num = 0;
00532                         while(i+j < points.size() && num < 3){
00533                                 Point p2 = points.get(i+j);
00534                                 Point prep2 = points.get(i+j-1);
00535                                 if(p2.v.distance(prep2.v) > 0.1){
00536                                         num++;
00537                                         if (p2.v.distance(p.v) < 0.1){
00538                                                 merge(p,prep2);
00539                                                 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);
00540                                                 for (Point p3 : points){
00541                                                         if(p3.v.distance(p.v) == 0 || p3.v.distance(prep2.v) == 0){
00542                                                                 p3.v = newPos;
00543                                                                 p3.color = 0xffff0000;
00544                                                         }
00545                                                 }
00546                                         }
00547                                 }
00548                                 j++;
00549                         }
00550                         i++;
00551                 }
00552         }
00553         
00554         public void getTransitionPoints(){
00555                 double threshDist = 0.0f;
00556                 double threshAngle = Math.PI * 00/180;
00557                 HashSet<Set<Point>> setOfSets = new HashSet<Set<Point>>(mergeSet.values());
00558                 for(Set<Point> s : setOfSets){
00559                         HashSet<Point> curSet = new HashSet<Point>(s);
00560                         for(Point p1 : s){
00561                                 curSet.remove(p1);
00562                                 for(Point p2 : curSet){
00563                                         // the first part is for searching forwards
00564                                         if(points.indexOf(p1)+1 < points.size() && points.indexOf(p2)+1 < points.size()){
00565                                                 Point succP1 = points.get(points.indexOf(p1)+1);
00566                                                 Point succP2 = points.get(points.indexOf(p2)+1);
00567                                                 // look only for real successor not merged points
00568                                                 if(p1.v.distance(succP1.v) != 0 && p2.v.distance(succP2.v) != 0){
00569                                                         Vector3f dir1 = new Vector3f(p1.v);
00570                                                         dir1.sub(succP1.v);
00571                                                         Vector3f dir2 = new Vector3f(p2.v);
00572                                                         dir2.sub(succP2.v);
00573                                                         double angle = dir1.angle(dir2);
00574                                                         // check for distance and angle threshold
00575                                                         if (succP1.v.distance(succP2.v) > threshDist && angle >= threshAngle){
00576                                                                 // check, whether the direction of the trajectory is the same!
00577                                                                 int k = 1;
00578                                                                 Point pre1 = new Point(p1);
00579                                                                 Point pre2 = new Point(p2);
00580                                                                 while(points.indexOf(p1)-k > 0){
00581                                                                         pre1 = points.get(points.indexOf(p1)-k);
00582                                                                         if (pre1.v.distance(p1.v) > 0.1){
00583                                                                                 k = 1;
00584                                                                                 break;
00585                                                                         }
00586                                                                         else
00587                                                                                 k++;
00588                                                                 }
00589                                                                 while(points.indexOf(p2)-k > 0){
00590                                                                         pre2 = points.get(points.indexOf(p2)-k);
00591                                                                         if (pre2.v.distance(p2.v) > 0.1){
00592                                                                                 break;
00593                                                                         }
00594                                                                         else
00595                                                                                 k++;
00596                                                                 }
00597                                                                 if(pre1.v.distance(pre2.v) > 0.1)
00598                                                                         continue;
00599                                                                 // however: we do not want to find 'fake' transition points in lines
00600                                                                 // where there was just a 'oversight' by the merging algorithm,
00601                                                                 // therefore we look whether the trajectories meet again soon
00602                                                                 int l = 1;
00603                                                                 int fut1 = 0;
00604                                                                 int fut2 = 0;
00605                                                                 Set<Point> succ1 = new HashSet<Point>();
00606                                                                 Set<Point> succ2 = new HashSet<Point>();
00607                                                                 while(points.indexOf(p1)+l < points.size() && points.indexOf(p2)+l < points.size()){
00608                                                                         if(fut1 < 4){
00609                                                                                 Point p11 = points.get(points.indexOf(p1)+l);
00610                                                                                 Point p12 = points.get(points.indexOf(p1)+l-1);
00611                                                                                 succ1.add(p11);
00612                                                                                 if(p11.v.distance(p12.v) >= range/200 && !mergeSet.get(p1).contains(p11)){
00613                                                                                         fut1++;
00614                                                                                 }
00615                                                                         }
00616                                                                         if(fut2 < 4){
00617                                                                                 Point p21 = points.get(points.indexOf(p2)+l);
00618                                                                                 Point p22 = points.get(points.indexOf(p2)+l-1);
00619                                                                                 succ2.add(p21);
00620                                                                                 if(p21.v.distance(p22.v) >= range/200 && !mergeSet.get(p1).contains(p21)){
00621                                                                                         fut2++;
00622                                                                                 }
00623                                                                         }
00624                                                                         l++;
00625                                                                 }
00626                                                                 boolean realTransition = true;
00627                                                                 for(Point pSucc1 : succ1){
00628                                                                         for(Point pSucc2 : succ2){
00629                                                                                 if(pSucc1.v.distance(pSucc2.v) <= range/200)
00630                                                                                         realTransition = false;
00631                                                                         }
00632                                                                 }
00633                                                                 if(realTransition){
00634                                                                         System.out.println(">>>>>>> Got a transition point");
00635                                                                         p1.size = range/75;
00636                                                                         p1.color = 0xff00ff00;
00637                                                                 }
00638                                                         }
00639                                                 }
00640                                         }
00641                                         // Same for the past!
00642                                         if(points.indexOf(p1)-1 > 0 && points.indexOf(p2)-1 > 0){
00643                                                 Point preP1 = points.get(points.indexOf(p1)-1);
00644                                                 Point preP2 = points.get(points.indexOf(p2)-1);
00645                                                 // look only for real predecessor not merged points
00646                                                 if(p1.v.distance(preP1.v) != 0 && p2.v.distance(preP2.v) != 0){
00647                                                         Vector3f dir1 = new Vector3f(p1.v);
00648                                                         dir1.sub(preP1.v);
00649                                                         Vector3f dir2 = new Vector3f(p2.v);
00650                                                         dir2.sub(preP2.v);
00651                                                         double angle = dir1.angle(dir2);
00652                                                         // check for distance and angle threshold
00653                                                         if (preP1.v.distance(preP2.v) > threshDist && angle >= threshAngle){
00654                                                                 // check, whether the direction of the trajectory is the same!
00655                                                                 int k = 1;
00656                                                                 Point succ1 = new Point(p1);
00657                                                                 Point succ2 = new Point(p2);
00658                                                                 while(points.indexOf(p1)+k < points.size()){
00659                                                                         succ1 = points.get(points.indexOf(p1)+k);
00660                                                                         if (succ1.v.distance(p1.v) > 0.1){
00661                                                                                 k = 1;
00662                                                                                 break;
00663                                                                         }
00664                                                                         else
00665                                                                                 k++;
00666                                                                 }
00667                                                                 while(points.indexOf(p2)+k < points.size()){
00668                                                                         succ2 = points.get(points.indexOf(p2)+k);
00669                                                                         if (succ2.v.distance(p2.v) > 0.1){
00670                                                                                 break;
00671                                                                         }
00672                                                                         else
00673                                                                                 k++;
00674                                                                 }
00675                                                                 if(succ1.v.distance(succ2.v) > 0.1)
00676                                                                         continue;
00677                                                                 int l = 1;
00678                                                                 int fut1 = 0;
00679                                                                 int fut2 = 0;
00680                                                                 Set<Point> prec1 = new HashSet<Point>();
00681                                                                 Set<Point> prec2 = new HashSet<Point>();
00682                                                                 while(points.indexOf(p1)-l > 0 && points.indexOf(p2)-l > 0){
00683                                                                         if(fut1 < 4){
00684                                                                                 Point p11 = points.get(points.indexOf(p1)-l);
00685                                                                                 Point p12 = points.get(points.indexOf(p1)-l+1);
00686                                                                                 prec1.add(p11);
00687                                                                                 if(p11.v.distance(p12.v) >= range/200 && !mergeSet.get(p1).contains(p11)){
00688                                                                                         fut1++;
00689                                                                                 }
00690                                                                         }
00691                                                                         if(fut2 < 4){
00692                                                                                 Point p21 = points.get(points.indexOf(p2)-l);
00693                                                                                 Point p22 = points.get(points.indexOf(p2)-l+1);
00694                                                                                 prec2.add(p21);
00695                                                                                 if(p21.v.distance(p22.v) >= range/200 && !mergeSet.get(p1).contains(p21)){
00696                                                                                         fut2++;
00697                                                                                 }
00698                                                                         }
00699                                                                         l++;
00700                                                                 }
00701                                                                 boolean realTransition = true;
00702                                                                 for(Point pSucc1 : prec1){
00703                                                                         for(Point pSucc2 : prec2){
00704                                                                                 if(pSucc1.v.distance(pSucc2.v) <= range/200)
00705                                                                                         realTransition = false;
00706                                                                         }
00707                                                                 }
00708                                                                 if(realTransition){
00709                                                                         System.out.println(">>>>>>> Got a transition point");
00710                                                                         p1.size = range/75;
00711                                                                         p1.color = 0xff00ff00;
00712                                                                 }
00713                                                         }
00714                                                 }
00715                                         }
00716                                 }
00717                         }
00718                 }
00719         }
00720 
00721         public int getMaxStep() {
00722                 return getNumSteps()-1;
00723         }
00724         
00725         public class PointPair implements Drawable {
00726 
00727                 protected Point p1, p2;
00728                 protected int linecolor;
00729                 
00730                 public PointPair(Point p1, Point p2, int linecolor) {
00731                         this.p1 = p2;
00732                         this.p2 = p2;
00733                         this.linecolor = linecolor;
00734                 }
00735                 
00736                 public void draw(Canvas c) {
00737                         p1.size = pointSize;
00738                         p2.size = pointSize;
00739                         p1.draw(c);
00740                         p2.draw(c);
00741                         c.drawLine(p1.v, p2.v, linecolor);
00742                 }               
00743         }
00744 }


mod_vis
Author(s): Moritz Tenorth, Jakob Engel
autogenerated on Mon Oct 6 2014 01:30:00