with class

Dependencies:   ISR_Mini-explorer mbed

Fork of VirtualForces by Georgios Tsamis

Files at this revision

API Documentation at this revision

Comitter:
Ludwigfr
Date:
Sun Jun 11 22:40:37 2017 +0000
Parent:
34:c208497dd079
Child:
36:b59d56d0b3b4
Commit message:
change so every command to the robot is in world coordinate

Changed in this revision

Map.cpp Show annotated file Show diff for this revision Revisions of this file
Map.hpp Show annotated file Show diff for this revision Revisions of this file
MiniExplorerCoimbra.cpp Show annotated file Show diff for this revision Revisions of this file
MiniExplorerCoimbra.hpp Show annotated file Show diff for this revision Revisions of this file
Sonar.cpp Show annotated file Show diff for this revision Revisions of this file
Sonar.hpp Show annotated file Show diff for this revision Revisions of this file
main.cpp Show annotated file Show diff for this revision Revisions of this file
--- a/Map.cpp	Fri Jun 09 14:30:21 2017 +0000
+++ b/Map.cpp	Sun Jun 11 22:40:37 2017 +0000
@@ -38,24 +38,10 @@
     return 1-1/(1+exp(lt));
 }
 
-
-//returns the log value that the cell is occupied from the probability value [0,1]
-float Map::proba_to_log(float p){
-    return log(p/(1-p));
-}
-
 void Map::update_cell_value(int widthIndice,int heightIndice ,float proba){
     this->cellsLogValues[widthIndice][heightIndice]=this->cellsLogValues[widthIndice][heightIndice]+this->proba_to_log(proba)+this->initialLogValues[widthIndice][heightIndice];//map is filled as map[0][0] get the data for the point closest to the origin
 }
 
-float Map::robot_x_coordinate_in_world(float robot_x, float robot_y){
-    return this->nbCellWidth*this->sizeCellWidth-robot_y;
-}
-
-float Map::robot_y_coordinate_in_world(float robot_x, float robot_y){
-    return robot_x;
-}
-
 float Map::cell_width_coordinate_to_world(int i){
 	return this->sizeCellWidth/2+i*this->sizeCellWidth;
 }
@@ -68,8 +54,22 @@
 	return  this->log_to_proba(this->cellsLogValues[widthIndice][heightIndice]);
 }
 
+//returns the log value that the cell is occupied from the probability value [0,1]
+float Map::proba_to_log(float p){
+    return log(p/(1-p));
+}
+
 /*
 
+float Map::robot_x_coordinate_in_world(float robot_x, float robot_y){
+    return this->nbCellWidth*this->sizeCellWidth-robot_y;
+}
+
+float Map::robot_y_coordinate_in_world(float robot_x, float robot_y){
+    return robot_x;
+}
+
+
 void MiniExplorerCoimbra::print_final_map() {
     float currProba;
     pc.printf("\n\r");
--- a/Map.hpp	Fri Jun 09 14:30:21 2017 +0000
+++ b/Map.hpp	Sun Jun 11 22:40:37 2017 +0000
@@ -48,21 +48,22 @@
     
     //Updates map value
     void update_cell_value(int widthIndice,int heightIndice ,float proba);
+
+    //fill initialLogValues with the values we already know (here the bordurs)
+    void fill_initialLogValues();
     
     //returns the probability [0,1] that the cell is occupied from the log valAue lt
     float log_to_proba(float lt);
 
     //returns the log value that the cell is occupied from the probability value [0,1]
     float proba_to_log(float p);
-
-    //fill initialLogValues with the values we already know (here the bordurs)
-    void fill_initialLogValues();
-
+    
+    /*
+    
     float robot_x_coordinate_in_world(float robot_x, float robot_y);
 
     float robot_y_coordinate_in_world(float robot_x, float robot_y);
     
-    /*
     void print_final_map();
 
     void print_final_map_with_robot_position(float robot_x,float robot_y);
--- a/MiniExplorerCoimbra.cpp	Fri Jun 09 14:30:21 2017 +0000
+++ b/MiniExplorerCoimbra.cpp	Sun Jun 11 22:40:37 2017 +0000
@@ -3,14 +3,14 @@
 
 #define PI 3.14159
 
-MiniExplorerCoimbra::MiniExplorerCoimbra(float defaultX, float defaultY, float defaultTheta):map(200,200,20,20),sonarLeft(10*PI/36,-4,4),sonarFront(0,0,5),sonarRight(-10*PI/36,4,4){
+MiniExplorerCoimbra::MiniExplorerCoimbra(float defaultXWorld, float defaultYWorld, float defaultThetaWorld):map(200,200,20,20),sonarLeft(10*PI/36,-4,4),sonarFront(0,0,5),sonarRight(-10*PI/36,4,4){
     i2c1.frequency(100000);
     initRobot(); //Initializing the robot
     pc.baud(9600); // baud for the pc communication
 
     measure_always_on();//TODO check if needed
 
-    this->setXYTheta(defaultX,defaultY,defaultTheta);
+    this->setXYThetaAndXYThetaWorld(defaultXWorld,defaultYWorld,defaultThetaWorld);
     this->radiusWheels=3.25;
     this->distanceWheels=7.2; 
     
@@ -25,10 +25,26 @@
     this->repulsionConstantForce=1;
 } 
 
-void MiniExplorerCoimbra::setXYTheta(float x, float y, float theta){
-    X=x;
-    Y=y;
-    theta=theta;
+void MiniExplorerCoimbra::setXYThetaAndXYThetaWorld(float defaultXWorld, float defaultYWorld, float defaultThetaWorld){
+    this->xWorld=defaultXWorld;
+    this->yWorld=defaultYWorld;
+    this->thetaWorld=defaultThetaWorld;
+    X=defaultYWorld;
+    Y=-defaultXWorld;
+	if(defaultThetaWorld < -PI/2)
+		theta=PI/2+PI-defaultThetaWorld;
+	else
+		theta=defaultThetaWorld-PI/2;
+}
+
+void MiniExplorerCoimbra::myOdometria(){
+	Odometria();
+	this->xWorld=-Y;
+	this->yWorld=X;
+	if(theta >PI/2)
+		this->thetaWorld=-PI+(theta-PI/2);
+	else
+		this->thetaWorld=theta+PI/2;
 }
 
 //generate a position randomly and makes the robot go there while updating the map
@@ -44,21 +60,21 @@
     if(signOfY  < 1)
         signOfY=-1;
         
-    float targetX = movementOnX*signOfX;
-    float targetY = movementOnY*signOfY;
-    float targetAngle = 2*((float)(rand()%31416)-15708)/10000.0;
-    this->go_to_point_with_angle(targetX, targetY, targetAngle);
+    float targetXWorld = movementOnX*signOfX;
+    float targetYWorld = movementOnY*signOfY;
+    float targetAngleWorld = 2*((float)(rand()%31416)-15708)/10000.0;
+    this->go_to_point_with_angle(targetXWorld, targetYWorld, targetAngleWorld);
 }
 
-//go the the given position while updating the map
-void MiniExplorerCoimbra::go_to_point_with_angle(float targetX, float targetY, float targetAngle) {
-    bool keep_going=true;
+//move of targetXWorld and targetYWorld ending in a targetAngleWorld
+void MiniExplorerCoimbra::go_to_point_with_angle(float targetXWorld, float targetYWorld, float targetAngleWorld) {
+    bool keepGoing=true;
     float leftMm;
     float frontMm; 
     float rightMm;
     float dt;
     Timer t;
-    float d2;
+    float distanceToTarget;
     do {
         //Timer stuff
         dt = t.read();
@@ -66,7 +82,7 @@
         t.start();
         
         //Updating X,Y and theta with the odometry values
-        Odometria();
+        this->myOdometria();
        	leftMm = get_distance_left_sensor();
     	frontMm = get_distance_front_sensor();
     	rightMm = get_distance_right_sensor();
@@ -77,102 +93,56 @@
             rightMotor(1,0);
             this->update_sonar_values(leftMm, frontMm, rightMm);
             //TODO Giorgos maybe you can also test the do_half_flip() function
-            Odometria();
+            this->myOdometria();
             //do a flip TODO
-            keep_going=false;
+            keepGoing=false;
             this->do_half_flip();   
         }else{
             //if not in danger zone continue as usual
             this->update_sonar_values(leftMm, frontMm, rightMm);
 
         	//Updating motor velocities
-            d2=this->update_angular_speed_wheels_go_to_point_with_angle(targetX,targetY,targetAngle,dt);
+            distanceToTarget=this->update_angular_speed_wheels_go_to_point_with_angle(targetXWorld,targetYWorld,targetAngleWorld,dt);
     
             wait(0.2);
             //Timer stuff
             t.stop();
-            pc.printf("\n\r dist to target= %f",d2);
+            pc.printf("\n\r dist to target= %f",distanceToTarget);
         }
-    } while(d2>1 && (abs(targetAngle-theta)>0.01) && keep_going);
+    } while(distanceToTarget>1 && (abs(targetAngleWorld-this->thetaWorld)>0.01) && keepGoing);
 
     //Stop at the end
     leftMotor(1,0);
     rightMotor(1,0);
 }
 
-void MiniExplorerCoimbra::update_sonar_values(float leftMm,float frontMm,float rightMm){
-    float xWorldCell;
-    float yWorldCell;
-    float xRobotWorld=this->get_converted_robot_X_into_world();
-    float yRobotWorld=this->get_converted_robot_Y_into_world();
-    for(int i=0;i<this->map.nbCellWidth;i++){
-        for(int j=0;j<this->map.nbCellHeight;j++){
-        	xWorldCell=this->map.cell_width_coordinate_to_world(i);
-            yWorldCell=this->map.cell_height_coordinate_to_world(j);
-            //compute_probability_t(float distanceObstacleDetected, float x, float y, float[2] robotCoordinatesInWorld)
-        	this->map.update_cell_value(i,j,this->sonarRight.compute_probability_t(rightMm,xWorldCell,yWorldCell,xRobotWorld,yRobotWorld,theta));
-        	this->map.update_cell_value(i,j,this->sonarLeft.compute_probability_t(leftMm,xWorldCell,yWorldCell,xRobotWorld,yWorldCell,theta));
-        	this->map.update_cell_value(i,j,this->sonarFront.compute_probability_t(frontMm,xWorldCell,yWorldCell,xRobotWorld,yWorldCell,theta));
-
-       	}
-    }
-}
-
-float MiniExplorerCoimbra::get_converted_robot_X_into_world(){
-	//x world coordinate
-	return this->map.nbCellWidth*this->map.sizeCellWidth-Y;
-}
-
-float MiniExplorerCoimbra::get_converted_robot_Y_into_world(){
-	//y worldcoordinate
-	return X;
-}
-
-void MiniExplorerCoimbra::do_half_flip(){
-    Odometria();
-    float theta_plus_h_pi=theta+PI/2;//theta is between -PI and PI
-    if(theta_plus_h_pi > PI)
-        theta_plus_h_pi=-(2*PI-theta_plus_h_pi);
-    leftMotor(0,100);
-    rightMotor(1,100);
-    while(abs(theta_plus_h_pi-theta)>0.05){
-        Odometria();
-       // pc.printf("\n\r diff=%f", abs(theta_plus_pi-theta));
-    }
-    leftMotor(1,0);
-    rightMotor(1,0);    
-}
-
-//Distance computation function
-float MiniExplorerCoimbra::dist(float robotX, float robotY, float targetX, float targetY){
-    //pc.printf("%f, %f, %f, %f",robotX,robotY,targetX,targetY);
-    return sqrt(pow(targetY-robotY,2) + pow(targetX-robotX,2));
-}
-
-float MiniExplorerCoimbra::update_angular_speed_wheels_go_to_point_with_angle(float targetX, float targetY, float targetAngle, float dt){
+float MiniExplorerCoimbra::update_angular_speed_wheels_go_to_point_with_angle(float targetXWorld, float targetYWorld, float targetAngleWorld, float dt){
     //compute_angles_and_distance
-    float alpha = atan2((targetY-Y),(targetX-X))-theta;
-    alpha = atan(sin(alpha)/cos(alpha));
-    float rho = this->dist(X, Y, targetX, targetY);
-    float d2 = rho;
-    float beta = -alpha-theta+targetAngle;        
+    //atan2 take the deplacement on x and the deplacement on y as parameters
+    float angleToPoint = atan2((targetYWorld-this->yWorld),(targetXWorld-this->xWorld))-this->thetaWorld;
+    angleToPoint = atan(sin(angleToPoint)/cos(angleToPoint));
+    //rho is the distance to the point of arrival
+    float rho = dist(targetXWorld,targetYWorld,this->xWorld,this->yWorld);
+    float distanceToTarget = rho;
+    //TODO check that
+    float beta = targetAngleWorld-angleToPoint-this->thetaWorld;        
     
     //Computing angle error and distance towards the target value
-    rho += dt*(-this->khro*cos(alpha)*rho);
-    float temp = alpha;
-    alpha += dt*(this->khro*sin(alpha)-this->ka*alpha-this->kb*beta);
+    rho += dt*(-this->khro*cos(angleToPoint)*rho);
+    float temp = angleToPoint;
+    angleToPoint += dt*(this->khro*sin(angleToPoint)-this->ka*angleToPoint-this->kb*beta);
     beta += dt*(-this->khro*sin(temp));
 
     //Computing linear and angular velocities
     float linear;
     float angular;
-    if(alpha>=-1.5708 && alpha<=1.5708){
+    if(angleToPoint>=-1.5708 && angleToPoint<=1.5708){
         linear=this->khro*rho;
-        angular=this->ka*alpha+this->kb*beta;
+        angular=this->ka*angleToPoint+this->kb*beta;
     }
     else{
         linear=-this->khro*rho;
-        angular=-this->ka*alpha-this->kb*beta;
+        angular=-this->ka*angleToPoint-this->kb*beta;
     }
     float angular_left=(linear-0.5*this->distanceWheels*angular)/this->radiusWheels;
     float angular_right=(linear+0.5*this->distanceWheels*angular)/this->radiusWheels;
@@ -190,12 +160,39 @@
     leftMotor(1,angular_left);
     rightMotor(1,angular_right);
     
-    return d2;
+    return distanceToTarget;
 }
 
+void MiniExplorerCoimbra::update_sonar_values(float leftMm,float frontMm,float rightMm){
+    float xWorldCell;
+    float yWorldCell;
+    for(int i=0;i<this->map.nbCellWidth;i++){
+        for(int j=0;j<this->map.nbCellHeight;j++){
+        	xWorldCell=this->map.cell_width_coordinate_to_world(i);
+            yWorldCell=this->map.cell_height_coordinate_to_world(j);
+            //compute_probability_t(float distanceObstacleDetected, float x, float y, float[2] robotCoordinatesInWorld)
+        	this->map.update_cell_value(i,j,this->sonarRight.compute_probability_t(rightMm,xWorldCell,yWorldCell,this->xWorld,this->yWorld,theta));
+        	this->map.update_cell_value(i,j,this->sonarLeft.compute_probability_t(leftMm,xWorldCell,yWorldCell,this->xWorld,yWorldCell,theta));
+        	this->map.update_cell_value(i,j,this->sonarFront.compute_probability_t(frontMm,xWorldCell,yWorldCell,this->xWorld,yWorldCell,theta));
+
+       	}
+    }
+}
+
+//Distance computation function
+float MiniExplorerCoimbra::dist(float x1, float y1, float x2, float y2){
+    return sqrt(pow(y2-y1,2) + pow(x2-x1,2));
+}
+
+//use virtual force field
 void MiniExplorerCoimbra::try_to_reach_target(float targetXWorld,float targetYWorld){
     //atan2 gives the angle beetween PI and -PI
-    float angleToTarget=atan2(targetXWorld,targetYWorld);
+    this->myOdometria();
+    /*
+    float deplacementOnXWorld=targetXWorld-this->xWorld;
+    float deplacementOnYWorld=targetYWorld-this->yWorld;
+    */
+    float angleToTarget=atan2(targetXWorld-this->xWorld,targetYWorld-this->yWorld);
     turn_to_target(angleToTarget);
     bool reached=false;
     int print=0;
@@ -205,15 +202,7 @@
         if(print==10){
             leftMotor(1,0);
             rightMotor(1,0);
-            /*
-            pc.printf("\r\n theta=%f", theta);
-            pc.printf("\r\n IN ORTHO:");
-            pc.printf("\r\n X Robot=%f", this->get_converted_robot_X_into_world());
-            pc.printf("\r\n Y Robot=%f", this->get_converted_robot_Y_into_world());
-            pc.printf("\r\n X Target=%f", targetXWorld);
-            pc.printf("\r\n Y Target=%f", targetYWorld);
-            */
-            this->print_final_map_with_robot_position_and_target(X,Y,targetXWorld,targetYWorld);
+            this->print_final_map_with_robot_position_and_target(targetXWorld,targetYWorld);
             print=0;
         }else
             print+=1;
@@ -230,10 +219,10 @@
     float line_b;
     float line_c;
     //Updating X,Y and theta with the odometry values
-    float forceX=0;
-    float forceY=0;
+    float forceXWorld=0;
+    float forceYWorld=0;
     //we update the odometrie
-    Odometria();
+    this->myOdometria();
     //we check the sensors
     float leftMm = get_distance_left_sensor();
     float frontMm = get_distance_front_sensor();
@@ -241,64 +230,58 @@
     //update the probabilities values 
     this->update_sonar_values(leftMm, frontMm, rightMm);
     //we compute the force on X and Y
-    this->compute_forceX_and_forceY(&forceX, &forceY,targetXWorld,targetYWorld);
+    this->compute_forceX_and_forceY(&forceXWorld, &forceYWorld,targetXWorld,targetYWorld);
     //we compute a new ine
-    this->calculate_line(forceX, forceY, &line_a,&line_b,&line_c);
+    this->calculate_line(forceXWorld, forceYWorld, &line_a,&line_b,&line_c);
     //Updating motor velocities
     this->go_to_line(line_a,line_b,line_c,targetXWorld,targetYWorld);
 
     //wait(0.1);
-    Odometria();
-    if(dist(this->get_converted_robot_X_into_world(),this->get_converted_robot_Y_into_world(),targetXWorld,targetYWorld)<10)
+    this->myOdometria();
+    if(dist(this->xWorld,this->yWorld,targetXWorld,targetYWorld)<10)
         *reached=true;
 }
 
 //compute the force on X and Y
-void MiniExplorerCoimbra::compute_forceX_and_forceY(float* forceX, float* forceY, float targetXWorld, float targetYWorld){
-     float xRobotWorld=this->get_converted_robot_X_into_world();
-     float yRobotWorld=this->get_converted_robot_Y_into_world();
-
+void MiniExplorerCoimbra::compute_forceX_and_forceY(float* forceXWorld, float* forceYWorld, float targetXWorld, float targetYWorld){
      float forceRepulsionComputedX=0;
      float forceRepulsionComputedY=0;
      //for each cell of the map we compute a force of repulsion
      for(int i=0;i<this->map.nbCellWidth;i++){
         for(int j=0;j<this->map.nbCellHeight;j++){
-            this->update_force(i,j,&forceRepulsionComputedX,&forceRepulsionComputedY,xRobotWorld,yRobotWorld);
+            this->update_force(i,j,&forceRepulsionComputedX,&forceRepulsionComputedY);
         }
     }
     //update with attraction force
-    *forceX=+forceRepulsionComputedX;
-    *forceY=+forceRepulsionComputedY;
-    float distanceTargetRobot=sqrt(pow(targetXWorld-xRobotWorld,2)+pow(targetYWorld-yRobotWorld,2));
+    *forceXWorld=+forceRepulsionComputedX;
+    *forceYWorld=+forceRepulsionComputedY;
+    float distanceTargetRobot=sqrt(pow(targetXWorld-this->xWorld,2)+pow(targetYWorld-this->yWorld,2));
     if(distanceTargetRobot != 0){
-        *forceX-=this->attractionConstantForce*(targetXWorld-xRobotWorld)/distanceTargetRobot;
-        *forceY-=this->attractionConstantForce*(targetYWorld-yRobotWorld)/distanceTargetRobot;
+        *forceXWorld-=this->attractionConstantForce*(targetXWorld-this->xWorld)/distanceTargetRobot;
+        *forceYWorld-=this->attractionConstantForce*(targetYWorld-this->yWorld)/distanceTargetRobot;
     }
-    float amplitude=sqrt(pow(*forceX,2)+pow(*forceY,2));
+    float amplitude=sqrt(pow(*forceXWorld,2)+pow(*forceYWorld,2));
     if(amplitude!=0){//avoid division by 0 if forceX and forceY  == 0
-        *forceX=*forceX/amplitude;
-        *forceY=*forceY/amplitude;
+        *forceXWorld=*forceXWorld/amplitude;
+        *forceYWorld=*forceYWorld/amplitude;
     }
 }
 
-void MiniExplorerCoimbra::update_force(int widthIndice, int heightIndice, float* forceX, float* forceY, float xRobotWorld, float yRobotWorld ){
+void MiniExplorerCoimbra::update_force(int widthIndice, int heightIndice, float* forceRepulsionComputedX, float* forceRepulsionComputedY ){
     //get the coordonate of the map and the robot in the ortonormal space
     float xWorldCell=this->map.cell_width_coordinate_to_world(widthIndice);
     float yWorldCell=this->map.cell_height_coordinate_to_world(heightIndice);
-
     //compute the distance beetween the cell and the robot
-    float distanceCellToRobot=sqrt(pow(xWorldCell-xRobotWorld,2)+pow(yWorldCell-yRobotWorld,2));
+    float distanceCellToRobot=sqrt(pow(xWorldCell-this->xWorld,2)+pow(yWorldCell-this->yWorld,2));
     //check if the cell is in range
     if(distanceCellToRobot <= this->rangeForce) {
         float probaCell=this->map.get_proba_cell(widthIndice,heightIndice);
-        float xForceComputed=this->repulsionConstantForce*probaCell*(xWorldCell-xRobotWorld)/pow(distanceCellToRobot,3);
-        float yForceComputed=this->repulsionConstantForce*probaCell*(yWorldCell-yRobotWorld)/pow(distanceCellToRobot,3);
-        *forceX+=xForceComputed;
-        *forceY+=yForceComputed;
+        *forceRepulsionComputedX+=this->repulsionConstantForce*probaCell*(xWorldCell-this->xWorld)/pow(distanceCellToRobot,3);
+        *forceRepulsionComputedY+=this->repulsionConstantForce*probaCell*(yWorldCell-this->yWorld)/pow(distanceCellToRobot,3);
     }
 }
 
-//robotX and robotY are from Odometria, calculate line_a, line_b and line_c
+//robotX and robotY are from this->myOdometria(), calculate line_a, line_b and line_c
 void MiniExplorerCoimbra::calculate_line(float forceX, float forceY, float *line_a, float *line_b, float *line_c){
     /*
     in the teachers maths it is 
@@ -309,7 +292,7 @@
     because a*x+b*y+c=0
     a impact the vertical and b the horizontal
     and he has to put them like this because
-    Robot space:      orthonormal space:
+    Robot space:      World space:
       ^                 ^
       |x                |y
    <- R                 O ->
@@ -319,7 +302,7 @@
     *line_a=forceX;
     *line_b=forceY;
     //because the line computed always pass by the robot center we dont need lince_c
-    //*line_c=forceX*yRobotWorld+forceY*xRobotWorld;    
+    //*line_c=forceX*this->yWorld+forceY*this->xWorld;    
     *line_c=0;
 }
 
@@ -330,41 +313,23 @@
     float linear;
     float angular; 
     
-    bool direction=true;
+    //atan2 use the deplacement on X and the deplacement on Y
+    float angleToTarget=atan2(targetXWorld-this->xWorld,targetYWorld-this->yWorld);
+    bool aligned=false;
+    
+    //this condition is passed if the target is in the same direction as the robot orientation
+   	if((angleToTarget>0 && this->thetaWorld > 0) || (angleToTarget<0 && this->thetaWorld <0))
+    	aligned=true;
     
-    //take as parameter how much the robot is supposed to move on x and y (world)
-    float angleToTarget=atan2(targetXWorld-this->get_converted_robot_X_into_world(),targetYWorld-this->get_converted_robot_Y_into_world());
-    bool inFront=true;
-    if(angleToTarget < 0)//the target is in front
-        inFront=false;
-
-    if(theta > 0){
-        //the robot is oriented to the left
-        if(theta > PI/2){
-            //the robot is oriented lower left
-            if(inFront)
-                direction=false;//robot and target not oriented the same way
-        }else{
-            //the robot is oriented upper left
-            if(!inFront)
-                direction=false;//robot and target not oriented the same way
-        }
-    }else{
-        //the robot is oriented to the right
-        if(theta < -PI/2){
-            //the robot is oriented lower right
-            if(inFront)
-                direction=false;//robot and target not oriented the same way
-        }else{ 
-            //the robot is oriented upper right
-            if(!inFront)
-                direction=false;//robot and target not oriented the same way
-        }
-    }
-    //pc.printf("\r\n Target is in front");
-    
+    //line angle is beetween pi/2 and -pi/2
+    /*
+    ax+by+c=0 (here c==0)
+    y=x*-a/b
+    if a*b > 0, the robot is going down
+    if a*b <0, the robot is going up
+    */	
      if(line_b!=0){
-        if(!direction)
+        if(!aligned)
             lineAngle=atan(-line_a/line_b);
         else
             lineAngle=atan(line_a/-line_b);
@@ -374,7 +339,7 @@
     }
     
     //Computing angle error
-    angleError = lineAngle-theta;
+    angleError = lineAngle-this->thetaWorld;//TODO that I m not sure
     angleError = atan(sin(angleError)/cos(angleError));
 
     //Calculating velocities
@@ -397,28 +362,12 @@
     rightMotor(this->sign2(angularRight),abs(angularRight));
 }
 
-//return 1 if positiv, -1 if negativ
-float MiniExplorerCoimbra::sign1(float value){
-    if(value>=0) 
-        return 1;
-    else 
-        return -1;
-}
-
-//return 1 if positiv, 0 if negativ
-int MiniExplorerCoimbra::sign2(float value){
-    if(value>=0) 
-        return 1;
-    else 
-        return 0;
-}
-
 /*angleToTarget is obtained through atan2 so it s:
 < 0 if the angle is bettween PI and 2pi on a trigo circle
 > 0 if it is between 0 and PI
 */
 void MiniExplorerCoimbra::turn_to_target(float angleToTarget){
-    Odometria();
+    this->myOdometria();
     float theta_plus_h_pi=theta+PI/2;//theta is between -PI and PI
     if(theta_plus_h_pi > PI)
         theta_plus_h_pi=-(2*PI-theta_plus_h_pi);
@@ -430,7 +379,7 @@
         rightMotor(0,1);
     }
     while(abs(angleToTarget-theta_plus_h_pi)>0.05){
-        Odometria();
+        this->myOdometria();
         theta_plus_h_pi=theta+PI/2;//theta is between -PI and PI
          if(theta_plus_h_pi > PI)
             theta_plus_h_pi=-(2*PI-theta_plus_h_pi);
@@ -440,31 +389,23 @@
     rightMotor(1,0);    
 }
 
+void MiniExplorerCoimbra::do_half_flip(){
+    this->myOdometria();
+    float theta_plus_h_pi=theta+PI/2;//theta is between -PI and PI
+    if(theta_plus_h_pi > PI)
+        theta_plus_h_pi=-(2*PI-theta_plus_h_pi);
+    leftMotor(0,100);
+    rightMotor(1,100);
+    while(abs(theta_plus_h_pi-theta)>0.05){
+        this->myOdometria();
+       // pc.printf("\n\r diff=%f", abs(theta_plus_pi-theta));
+    }
+    leftMotor(1,0);
+    rightMotor(1,0);    
+}
 
-/*
-//x and y passed are TargetNotMap
-float get_error_angles(float x, float y,float theta){
-    float angleBeetweenRobotAndTarget=atan2(y,x);
-    if(y > 0){
-        if(angleBeetweenRobotAndTarget < PI/2)//up right
-            angleBeetweenRobotAndTarget=-PI/2+angleBeetweenRobotAndTarget;
-        else//up right
-            angleBeetweenRobotAndTarget=angleBeetweenRobotAndTarget-PI/2;
-    }else{
-        if(angleBeetweenRobotAndTarget > -PI/2)//lower right
-            angleBeetweenRobotAndTarget=angleBeetweenRobotAndTarget-PI/2;
-        else//lower left
-            angleBeetweenRobotAndTarget=2*PI+angleBeetweenRobotAndTarget-PI/2;
-    }
-    return angleBeetweenRobotAndTarget-theta;
-}
-*/
-
-
-void MiniExplorerCoimbra::print_final_map_with_robot_position(float robot_x,float robot_y) {
+void MiniExplorerCoimbra::print_final_map_with_robot_position() {
     float currProba;
-    float Xrobot=this->map.robot_x_coordinate_in_world(robot_x,robot_y);
-    float Yrobot=this->map.robot_y_coordinate_in_world(robot_x,robot_y);
     
     float heightIndiceInOrthonormal;
     float widthIndiceInOrthonormal;
@@ -480,7 +421,7 @@
         for (int x= 0; x<this->map.nbCellWidth; x++) {
             heightIndiceInOrthonormal=this->map.cell_height_coordinate_to_world(y);
             widthIndiceInOrthonormal=this->map.cell_width_coordinate_to_world(x);
-            if(Yrobot >= (heightIndiceInOrthonormal+heightMalus) && Yrobot <= (heightIndiceInOrthonormal+heightBonus) && Xrobot >= (widthIndiceInOrthonormal+widthMalus) && Xrobot <= (widthIndiceInOrthonormal+widthBonus))                    
+            if(this->yWorld >= (heightIndiceInOrthonormal+heightMalus) && this->yWorld <= (heightIndiceInOrthonormal+heightBonus) && this->xWorld >= (widthIndiceInOrthonormal+widthMalus) && this->xWorld <= (widthIndiceInOrthonormal+widthBonus))                    
                 pc.printf(" R ");
             else{
                 currProba=this->map.log_to_proba(this->map.cellsLogValues[x][y]);
@@ -498,10 +439,8 @@
     }
 }
 
-void MiniExplorerCoimbra::print_final_map_with_robot_position_and_target(float robot_x,float robot_y,float targetXWorld, float targetYWorld) {
+void MiniExplorerCoimbra::print_final_map_with_robot_position_and_target(float targetXWorld, float targetYWorld) {
     float currProba;
-    float Xrobot=this->map.robot_x_coordinate_in_world(robot_x,robot_y);
-    float Yrobot=this->map.robot_y_coordinate_in_world(robot_x,robot_y);
     
     float heightIndiceInOrthonormal;
     float widthIndiceInOrthonormal;
@@ -517,7 +456,7 @@
         for (int x= 0; x<this->map.nbCellWidth; x++) {
             heightIndiceInOrthonormal=this->map.cell_height_coordinate_to_world(y);
             widthIndiceInOrthonormal=this->map.cell_width_coordinate_to_world(x);
-            if(Yrobot >= (heightIndiceInOrthonormal+heightMalus) && Yrobot <= (heightIndiceInOrthonormal+heightBonus) && Xrobot >= (widthIndiceInOrthonormal+widthMalus) && Xrobot <= (widthIndiceInOrthonormal+widthBonus))
+            if(this->yWorld >= (heightIndiceInOrthonormal+heightMalus) && this->yWorld <= (heightIndiceInOrthonormal+heightBonus) && this->xWorld >= (widthIndiceInOrthonormal+widthMalus) && this->xWorld <= (widthIndiceInOrthonormal+widthBonus))
                 pc.printf(" R ");
             else{
                 if(targetYWorld >= (heightIndiceInOrthonormal+heightMalus) && targetYWorld <= (heightIndiceInOrthonormal+heightBonus) && targetXWorld >= (widthIndiceInOrthonormal+widthMalus) && targetXWorld <= (widthIndiceInOrthonormal+widthBonus))                    
@@ -557,3 +496,49 @@
         pc.printf("\n\r");
     }
 }
+
+//return 1 if positiv, -1 if negativ
+float MiniExplorerCoimbra::sign1(float value){
+    if(value>=0) 
+        return 1;
+    else 
+        return -1;
+}
+
+//return 1 if positiv, 0 if negativ
+int MiniExplorerCoimbra::sign2(float value){
+    if(value>=0) 
+        return 1;
+    else 
+        return 0;
+}
+
+/*UNUSED
+float MiniExplorerCoimbra::get_converted_robot_X_into_world(){
+	//x world coordinate
+	return this->map.nbCellWidth*this->map.sizeCellWidth-Y;
+}
+
+float MiniExplorerCoimbra::get_converted_robot_Y_into_world(){
+	//y worldcoordinate
+	return X;
+}
+
+
+//x and y passed are TargetNotMap
+float get_error_angles(float x, float y,float theta){
+    float angleBeetweenRobotAndTarget=atan2(y,x);
+    if(y > 0){
+        if(angleBeetweenRobotAndTarget < PI/2)//up right
+            angleBeetweenRobotAndTarget=-PI/2+angleBeetweenRobotAndTarget;
+        else//up right
+            angleBeetweenRobotAndTarget=angleBeetweenRobotAndTarget-PI/2;
+    }else{
+        if(angleBeetweenRobotAndTarget > -PI/2)//lower right
+            angleBeetweenRobotAndTarget=angleBeetweenRobotAndTarget-PI/2;
+        else//lower left
+            angleBeetweenRobotAndTarget=2*PI+angleBeetweenRobotAndTarget-PI/2;
+    }
+    return angleBeetweenRobotAndTarget-theta;
+}
+*/
\ No newline at end of file
--- a/MiniExplorerCoimbra.hpp	Fri Jun 09 14:30:21 2017 +0000
+++ b/MiniExplorerCoimbra.hpp	Sun Jun 11 22:40:37 2017 +0000
@@ -6,18 +6,27 @@
 #include<math.h>
 
 
+
+
 	/*
-Robot coordinate system:      World coordinate system:
-      ^                 				^
-      |x                				|y
-   <--R                 				O-->
-    y                     				 x
+Robot coordinate system:      			World coordinate system:
+      ^                 							^
+      |x                							|y
+   <--R                 							O-->
+    y                     							x
+    
+angles from pi/2 to 3pi/2->0 to pi              angles from 0 to pi->0 to pi 
+angles from pi/2 to -pi/2->0 to -pi				angles from pi to 2pi-> -pi to 0
+
+	The idea is that for every command to the robot we use to world coodinate system 
 */
 
 class MiniExplorerCoimbra {
 	
 	public:
-	
+	float xWorld;
+	float yWorld;
+	float thetaWorld;
 	Map map;
 	Sonar sonarLeft;
 	Sonar sonarFront;
@@ -35,49 +44,40 @@
 	float attractionConstantForce;
 	float repulsionConstantForce;
 
-	MiniExplorerCoimbra(float defaultX, float defaultY, float defaultTheta);
+	MiniExplorerCoimbra(float defaultXWorld, float defaultYWorld, float defaultThetaWorld);
 
-	void setXYTheta(float x, float y, float theta);
+	void setXYThetaAndXYThetaWorld(float defaultXWorld, float defaultYWorld, float defaultThetaWorld);
+	
+	void myOdometria();
 	
 	//generate a position randomly and makes the robot go there while updating the map
 	void randomize_and_map();
 	
-	//go the the given position while updating the map
-	void go_to_point_with_angle(float targetX, float targetY, float targetAngle);
+	//move of targetXWorld and targetYWorld ending in a targetAngleWorld
+	void go_to_point_with_angle(float targetXWorld, float targetYWorld, float targetAngleWorld);
 	
 	void update_sonar_values(float leftMm,float frontMm,float rightMm);
 	
-	float get_converted_robot_X_into_world();
-	
-	float get_converted_robot_Y_into_world();
-	
-	void do_half_flip();
+	//Distance computation function
+	float dist(float x1, float y1, float x2, float y2);
 	
-	//Distance computation function
-	float dist(float robotX, float robotY, float targetX, float targetY);
-	
-	float update_angular_speed_wheels_go_to_point_with_angle(float targetX, float targetY, float targetAngle, float dt);
-	
+	//use virtual force field
 	void try_to_reach_target(float targetXWorld,float targetYWorld);
 	
 	void vff(bool* reached, float targetXWorld, float targetYWorld);
 	
 	//compute the force on X and Y
-	void compute_forceX_and_forceY(float* forceX, float* forceY, float targetXWorld, float targetYWorld);
+	void compute_forceX_and_forceY(float* forceXWorld, float* forceYWorld, float targetXWorld, float targetYWorld);
 	
-	void update_force(int widthIndice, int heightIndice, float* forceX, float* forceY, float xRobotWorld, float yRobotWorld );
+	void update_force(int widthIndice, int heightIndice, float* forceRepulsionComputedX, float* forceRepulsionComputedY );
 	
-	//robotX and robotY are from Odometria, calculate line_a, line_b and line_c
 	void calculate_line(float forceX, float forceY, float *line_a, float *line_b, float *line_c);
 	
 	//currently line_c is not used
 	void go_to_line(float line_a, float line_b, float line_c,float targetXWorld, float targetYWorld);
 	
-	//return 1 if positiv, -1 if negativ
-	float sign1(float value);
 	
-	//return 1 if positiv, 0 if negativ
-	int sign2(float value);
+	float update_angular_speed_wheels_go_to_point_with_angle(float targetXWorld, float targetYWorld, float targetAngleWorld, float dt);
 	
 	/*angleToTarget is obtained through atan2 so it s:
 	< 0 if the angle is bettween PI and 2pi on a trigo circle
@@ -85,11 +85,19 @@
 	*/
 	void turn_to_target(float angleToTarget);
 	
+	void do_half_flip();
+	
+	void print_final_map_with_robot_position();
+	
+	void print_final_map_with_robot_position_and_target(float targetXWorld, float targetYWorld);
+	
 	void print_final_map();
 	
-	void print_final_map_with_robot_position(float robot_x,float robot_y);
+	//return 1 if positiv, -1 if negativ
+	float sign1(float value);
 	
-	void print_final_map_with_robot_position_and_target(float robot_x,float robot_y,float targetXWorld, float targetYWorld);
+	//return 1 if positiv, 0 if negativ
+	int sign2(float value);
 };
 
 
--- a/Sonar.cpp	Fri Jun 09 14:30:21 2017 +0000
+++ b/Sonar.cpp	Sun Jun 11 22:40:37 2017 +0000
@@ -4,8 +4,8 @@
 
 Sonar::Sonar(float angleFromCenter, float distanceXFromRobotCenter, float distanceYFromRobotCenter ){
 	this->angleFromCenter=angleFromCenter;
-	this->distanceX=-distanceYFromRobotCenter;
-	this->distanceY=distanceXFromRobotCenter;
+	this->distanceX=distanceXFromRobotCenter;
+	this->distanceY=distanceYFromRobotCenter;
 	this->maxRange=50;//cm
 	this->minRange=10;//Rmin cm
 	this->incertitudeRange=10;//cm
--- a/Sonar.hpp	Fri Jun 09 14:30:21 2017 +0000
+++ b/Sonar.hpp	Sun Jun 11 22:40:37 2017 +0000
@@ -14,7 +14,7 @@
 	float distanceX;
 	float distanceY;
 	
-
+	//the distance are in the world coordinates
 	Sonar(float anlgeFromCenter, float distanceXFromRobotCenter, float distanceYFromRobotCenter );
 
 	//ODOMETRIA MUST HAVE BEEN CALLED
--- a/main.cpp	Fri Jun 09 14:30:21 2017 +0000
+++ b/main.cpp	Sun Jun 11 22:40:37 2017 +0000
@@ -1,8 +1,6 @@
 #include "MiniExplorerCoimbra.hpp"
 
-#define PI 3.14159
-
 int main(){ 
-    MiniExplorerCoimbra myRobot(0,0,0);   
+    MiniExplorerCoimbra myRobot(0,0,0);
     return 0;
 }