Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: ISR_Mini-explorer mbed
Revision 0:9f7ee7ed13e4, committed 2017-06-26
- Comitter:
- Ludwigfr
- Date:
- Mon Jun 26 12:05:20 2017 +0000
- Commit message:
- this version should work, though it would be nice to test all the lab demo; there's also some code on the 4th lab at the end of MiniExplorerCoimbra.cpp
Changed in this revision
diff -r 000000000000 -r 9f7ee7ed13e4 ISR_Mini-explorer.lib --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/ISR_Mini-explorer.lib Mon Jun 26 12:05:20 2017 +0000 @@ -0,0 +1,1 @@ +http://mbed.org/users/ISR/code/ISR_Mini-explorer/#15a30802e719
diff -r 000000000000 -r 9f7ee7ed13e4 Map.cpp
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/Map.cpp Mon Jun 26 12:05:20 2017 +0000
@@ -0,0 +1,177 @@
+#include "Map.hpp"
+
+Map::Map(float widthRealMap, float heightRealMap, int nbCellWidth, int nbCellHeight){
+ this->widthRealMap=widthRealMap;
+ this->heightRealMap=heightRealMap;
+ this->nbCellWidth=nbCellWidth;
+ this->nbCellHeight=nbCellHeight;
+ this->sizeCellWidth=widthRealMap/(float)nbCellWidth;
+ this->sizeCellHeight=heightRealMap/(float)nbCellHeight;
+
+ this->cellsLogValues= new float*[nbCellWidth];
+ for(int i = 0; i < nbCellWidth; ++i)
+ this->cellsLogValues[i] = new float[nbCellHeight];
+
+ this->initialLogValues= new float*[nbCellWidth];
+ for(int i = 0; i < nbCellWidth; ++i)
+ this->initialLogValues[i] = new float[nbCellHeight];
+
+ this->fill_initialLogValues();
+}
+
+//fill initialLogValues with the values we already know (here the bordurs)
+void Map::fill_initialLogValues(){
+ //Fill map, we know the border are occupied
+ for (int i = 0; i<this->nbCellWidth; i++) {
+ for (int j = 0; j<this->nbCellHeight; j++) {
+ if(j==0 || j==this->nbCellHeight-1 || i==0 || i==this->nbCellWidth-1)
+ this->initialLogValues[i][j] = this->proba_to_log(1);
+ else
+ this->initialLogValues[i][j] = this->proba_to_log(0.5);
+ }
+ }
+}
+
+void Map::fill_map_with_initial(){
+ for (int i = 0; i<this->nbCellWidth; i++) {
+ for (int j = 0; j<this->nbCellHeight; j++) {
+ this->cellsLogValues[i][j] = initialLogValues[i][j];
+ }
+ }
+}
+
+//returns the probability [0,1] that the cell is occupied from the log valAue lt
+float Map::log_to_proba(float lt){
+ return 1-1/(1+exp(lt));
+}
+
+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::cell_width_coordinate_to_world(int i){
+ return this->sizeCellWidth/2+i*this->sizeCellWidth;
+}
+
+float Map::cell_height_coordinate_to_world(int j){
+ return this->sizeCellHeight/2+j*this->sizeCellHeight;
+}
+
+float Map::get_proba_cell(int widthIndice, int heightIndice){
+ 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");
+ for (int y = this->nbCellHeight -1; y>-1; y--) {
+ for (int x= 0; x<this->nbCellWidth; x++) {
+ currProba=this->log_to_proba(this->cellsLogValues[x][y]);
+ if ( currProba < 0.5) {
+ pc.printf(" ");
+ } else {
+ if(currProba==0.5)
+ pc.printf(" . ");
+ else
+ pc.printf(" X ");
+ }
+ }
+ pc.printf("\n\r");
+ }
+}
+
+
+void Map::print_final_map_with_robot_position(float robot_x,float robot_y) {
+ float currProba;
+ float Xrobot=this->robot_x_coordinate_in_world(robot_x,robot_y);
+ float Yrobot=this->robot_y_coordinate_in_world(robot_x,robot_y);
+
+ float heightIndiceInOrthonormal;
+ float widthIndiceInOrthonormal;
+
+ float widthMalus=-(3*sizeCellWidth/2);
+ float widthBonus=sizeCellWidth/2;
+
+ float heightMalus=-(3*sizeCellHeight/2);
+ float heightBonus=sizeCellHeight/2;
+
+ pc.printf("\n\r");
+ for (int y = this->nbCellHeight -1; y>-1; y--) {
+ for (int x= 0; x<this->nbCellWidth; x++) {
+ heightIndiceInOrthonormal=this->cell_height_coordinate_to_world(y);
+ widthIndiceInOrthonormal=this->cell_width_coordinate_to_world(x);
+ if(Yrobot >= (heightIndiceInOrthonormal+heightMalus) && Yrobot <= (heightIndiceInOrthonormal+heightBonus) && Xrobot >= (widthIndiceInOrthonormal+widthMalus) && Xrobot <= (widthIndiceInOrthonormal+widthBonus))
+ pc.printf(" R ");
+ else{
+ currProba=this->log_to_proba(this->cellsLogValues[x][y]);
+ if ( currProba < 0.5)
+ pc.printf(" ");
+ else{
+ if(currProba==0.5)
+ pc.printf(" . ");
+ else
+ pc.printf(" X ");
+ }
+ }
+ }
+ pc.printf("\n\r");
+ }
+}
+
+void Map::print_final_map_with_robot_position_and_target(float robot_x,float robot_y,float targetXWorld, float targetYWorld) {
+ float currProba;
+ float Xrobot=this->robot_x_coordinate_in_world(robot_x,robot_y);
+ float Yrobot=this->robot_y_coordinate_in_world(robot_x,robot_y);
+
+ float heightIndiceInOrthonormal;
+ float widthIndiceInOrthonormal;
+
+ float widthMalus=-(3*sizeCellWidth/2);
+ float widthBonus=sizeCellWidth/2;
+
+ float heightMalus=-(3*sizeCellHeight/2);
+ float heightBonus=sizeCellHeight/2;
+
+ pc.printf("\n\r");
+ for (int y = this->nbCellHeight -1; y>-1; y--) {
+ for (int x= 0; x<this->nbCellWidth; x++) {
+ heightIndiceInOrthonormal=this->cell_height_coordinate_to_world(y);
+ widthIndiceInOrthonormal=this->cell_width_coordinate_to_world(x);
+ if(Yrobot >= (heightIndiceInOrthonormal+heightMalus) && Yrobot <= (heightIndiceInOrthonormal+heightBonus) && Xrobot >= (widthIndiceInOrthonormal+widthMalus) && Xrobot <= (widthIndiceInOrthonormal+widthBonus))
+ pc.printf(" R ");
+ else{
+ if(targetYWorld >= (heightIndiceInOrthonormal+heightMalus) && targetYWorld <= (heightIndiceInOrthonormal+heightBonus) && targetXWorld >= (widthIndiceInOrthonormal+widthMalus) && targetXWorld <= (widthIndiceInOrthonormal+widthBonus))
+ pc.printf(" T ");
+ else{
+ currProba=this->log_to_proba(this->cellsLogValues[x][y]);
+ if ( currProba < 0.5)
+ pc.printf(" ");
+ else{
+ if(currProba==0.5)
+ pc.printf(" . ");
+ else
+ pc.printf(" X ");
+ }
+ }
+ }
+ }
+ pc.printf("\n\r");
+ }
+}
+*/
\ No newline at end of file
diff -r 000000000000 -r 9f7ee7ed13e4 Map.hpp
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/Map.hpp Mon Jun 26 12:05:20 2017 +0000
@@ -0,0 +1,80 @@
+#ifndef MAP_HPP
+#define MAP_HPP
+
+#include<math.h>
+
+/*
+Robot coordinate system: World coordinate system:
+ ^ ^
+ |x |y
+ <--R O-->
+ y x
+
+Screen coordinate system
+ x
+ O--->
+y|
+ v
+
+how the float[2] arrays stock the position
+Start at 0,0 end top right
+^
+|heightIndice
+|
+_____>
+widthIndice
+*/
+
+
+class Map {
+
+public:
+ float widthRealMap;
+ float heightRealMap;
+ int nbCellWidth;
+ int nbCellHeight;
+ float sizeCellWidth;
+ float sizeCellHeight;
+ float** cellsLogValues;
+ float** initialLogValues;
+
+ Map(float widthRealMap, float heightRealMap, int nbCellWidth, int nbCellHeight);
+
+ float cell_width_coordinate_to_world(int i);
+
+ float cell_height_coordinate_to_world(int j);
+
+ float get_proba_cell(int widthIndice, int heightIndice);
+
+ void fill_map_with_initial();
+
+ //Updates map value
+ void update_cell_value(int widthIndice,int heightIndice ,float proba);
+
+ //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);
+
+ private:
+
+ //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);
+
+ void print_final_map_with_robot_position_and_target(float robot_x,float robot_y,float targetXWolrd, float targetYWorld);
+ */
+};
+
+#endif
+
diff -r 000000000000 -r 9f7ee7ed13e4 MiniExplorerCoimbra.cpp
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/MiniExplorerCoimbra.cpp Mon Jun 26 12:05:20 2017 +0000
@@ -0,0 +1,1016 @@
+#include "MiniExplorerCoimbra.hpp"
+#include "robot.h"
+
+#define PI 3.14159
+
+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->setXYThetaAndXYThetaWorld(defaultXWorld,defaultYWorld,defaultThetaWorld);
+ this->radiusWheels=3.25;
+ this->distanceWheels=7.2;
+
+ this->khro=12;
+ this->ka=30;
+ this->kb=-13;
+ this->kv=200;
+ this->kh=200;
+
+ this->rangeForce=30;
+ this->attractionConstantForce=10000;
+ this->repulsionConstantForce=1;
+}
+
+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
+void MiniExplorerCoimbra::randomize_and_map() {
+ //TODO check that it's aurelien's work
+ float movementOnX=rand()%(int)(this->map.widthRealMap/2);
+ float movementOnY=rand()%(int)(this->map.heightRealMap/2);
+
+ float signOfX=rand()%2;
+ if(signOfX < 1)
+ signOfX=-1;
+ float signOfY=rand()%2;
+ if(signOfY < 1)
+ signOfY=-1;
+
+ 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);
+}
+
+//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 distanceToTarget;
+ do {
+ //Timer stuff
+ dt = t.read();
+ t.reset();
+ t.start();
+
+ //Updating X,Y and theta with the odometry values
+ this->myOdometria();
+ leftMm = get_distance_left_sensor();
+ frontMm = get_distance_front_sensor();
+ rightMm = get_distance_right_sensor();
+
+ //if in dangerzone
+ if((frontMm < 150 && frontMm > 0)|| (leftMm <150 && leftMm > 0) || (rightMm <150 && rightMm > 0) ){
+ leftMotor(1,0);
+ rightMotor(1,0);
+ this->update_sonar_values(leftMm, frontMm, rightMm);
+ //TODO Giorgos maybe you can also test the do_half_flip() function
+ this->myOdometria();
+ //do a flip TODO
+ 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
+ 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",distanceToTarget);
+ }
+ } while(distanceToTarget>1 && (abs(targetAngleWorld-this->thetaWorld)>0.01) && keepGoing);
+
+ //Stop at the end
+ leftMotor(1,0);
+ rightMotor(1,0);
+}
+
+float MiniExplorerCoimbra::update_angular_speed_wheels_go_to_point_with_angle(float targetXWorld, float targetYWorld, float targetAngleWorld, float dt){
+ //compute_angles_and_distance
+ //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(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(angleToPoint>=-1.5708 && angleToPoint<=1.5708){
+ linear=this->khro*rho;
+ angular=this->ka*angleToPoint+this->kb*beta;
+ }
+ else{
+ linear=-this->khro*rho;
+ 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;
+
+ //Normalize speed for motors
+ if(angular_left>angular_right) {
+ angular_right=this->speed*angular_right/angular_left;
+ angular_left=this->speed;
+ } else {
+ angular_left=this->speed*angular_left/angular_right;
+ angular_right=this->speed;
+ }
+
+ //compute_linear_angular_velocities
+ leftMotor(1,angular_left);
+ rightMotor(1,angular_right);
+
+ 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);
+ this->map.update_cell_value(i,j,this->sonarRight.compute_probability_t(rightMm/10,xWorldCell,yWorldCell,this->xWorld,this->yWorld,this->thetaWorld));
+ this->map.update_cell_value(i,j,this->sonarLeft.compute_probability_t(leftMm/10,xWorldCell,yWorldCell,this->xWorld,this->yWorld,this->thetaWorld));
+ this->map.update_cell_value(i,j,this->sonarFront.compute_probability_t(frontMm/10,xWorldCell,yWorldCell,this->xWorld,this->yWorld,this->thetaWorld));
+
+ }
+ }
+}
+
+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);
+}
+
+//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
+ this->myOdometria();
+ /*
+ float deplacementOnXWorld=targetXWorld-this->xWorld;
+ float deplacementOnYWorld=targetYWorld-this->yWorld;
+ */
+ float angleToTarget=atan2(targetYWorld-this->yWorld,targetXWorld-this->xWorld);
+ turn_to_target(angleToTarget);
+ bool reached=false;
+ int print=0;
+ while (!reached) {
+ this->vff(&reached,targetXWorld,targetYWorld);
+ //test_got_to_line(&reached);
+ if(print==10){
+ leftMotor(1,0);
+ rightMotor(1,0);
+ this->print_map_with_robot_position_and_target(targetXWorld,targetYWorld);
+ print=0;
+ }else
+ print+=1;
+ }
+ //Stop at the end
+ leftMotor(1,0);
+ rightMotor(1,0);
+ pc.printf("\r\n target reached");
+ wait(3);//
+}
+
+void MiniExplorerCoimbra::vff(bool* reached, float targetXWorld, float targetYWorld){
+ float line_a;
+ float line_b;
+ float line_c;
+ //Updating X,Y and theta with the odometry values
+ float forceXWorld=0;
+ float forceYWorld=0;
+ //we update the odometrie
+ this->myOdometria();
+ //we check the sensors
+ float leftMm = get_distance_left_sensor();
+ float frontMm = get_distance_front_sensor();
+ float rightMm = get_distance_right_sensor();
+ //update the probabilities values
+ this->update_sonar_values(leftMm, frontMm, rightMm);
+ //we compute the force on X and Y
+ this->compute_forceX_and_forceY(&forceXWorld, &forceYWorld,targetXWorld,targetYWorld);
+ //we compute a new ine
+ 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);
+ this->myOdometria();
+ if(dist(this->xWorld,this->yWorld,targetXWorld,targetYWorld)<10)
+ *reached=true;
+}
+
+/*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){
+ 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);
+ if(angleToTarget>0){
+ leftMotor(0,1);
+ rightMotor(1,1);
+ }else{
+ leftMotor(1,1);
+ rightMotor(0,1);
+ }
+ while(abs(angleToTarget-theta_plus_h_pi)>0.05){
+ 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);
+ //pc.printf("\n\r diff=%f", abs(angleToTarget-theta_plus_h_pi));
+ }
+ leftMotor(1,0);
+ rightMotor(1,0);
+}
+
+
+void MiniExplorerCoimbra::print_map_with_robot_position_and_target(float targetXWorld, float targetYWorld) {
+ float currProba;
+
+ float heightIndiceInOrthonormal;
+ float widthIndiceInOrthonormal;
+
+ float widthMalus=-(3*this->map.sizeCellWidth/2);
+ float widthBonus=this->map.sizeCellWidth/2;
+
+ float heightMalus=-(3*this->map.sizeCellHeight/2);
+ float heightBonus=this->map.sizeCellHeight/2;
+
+ pc.printf("\n\r");
+ for (int y = this->map.nbCellHeight -1; y>-1; y--) {
+ 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(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))
+ pc.printf(" T ");
+ else{
+ currProba=this->map.log_to_proba(this->map.cellsLogValues[x][y]);
+ if ( currProba < 0.5)
+ pc.printf(" ");
+ else{
+ if(currProba==0.5)
+ pc.printf(" . ");
+ else
+ pc.printf(" X ");
+ }
+ }
+ }
+ }
+ pc.printf("\n\r");
+ }
+}
+
+
+//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
+
+ *line_a=forceY;
+ *line_b=-forceX;
+
+ 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: World space:
+ ^ ^
+ |x |y
+ <- R O ->
+ y x
+ but since our forceX, forceY are already computed in the orthonormal space I m not sure we need to
+ */
+ *line_a=forceX;
+ *line_b=forceY;
+ //because the line computed always pass by the robot center we dont need lince_c
+ //*line_c=forceX*this->yWorld+forceY*this->xWorld;
+ *line_c=0;
+}
+//compute the force on X and Y
+void MiniExplorerCoimbra::compute_forceX_and_forceY(float* forceXWorld, float* forceYWorld, float targetXWorld, float targetYWorld){
+ float forceRepulsionComputedX=0;
+ float forceRepulsionComputedY=0;
+ for(int i=0;i<this->map.nbCellWidth;i++){ //for each cell of the map we compute a force of repulsion
+ for(int j=0;j<this->map.nbCellHeight;j++){
+ this->update_force(i,j,&forceRepulsionComputedX,&forceRepulsionComputedY);
+ }
+ }
+ //update with attraction force
+ *forceXWorld=+forceRepulsionComputedX;
+ *forceYWorld=+forceRepulsionComputedY;
+ float distanceTargetRobot=sqrt(pow(targetXWorld-this->xWorld,2)+pow(targetYWorld-this->yWorld,2));
+ if(distanceTargetRobot != 0){
+ *forceXWorld-=this->attractionConstantForce*(targetXWorld-this->xWorld)/distanceTargetRobot;
+ *forceYWorld-=this->attractionConstantForce*(targetYWorld-this->yWorld)/distanceTargetRobot;
+ }
+ float amplitude=sqrt(pow(*forceXWorld,2)+pow(*forceYWorld,2));
+ if(amplitude!=0){//avoid division by 0 if forceX and forceY == 0
+ *forceXWorld=*forceXWorld/amplitude;
+ *forceYWorld=*forceYWorld/amplitude;
+ }
+}
+
+//currently line_c is not used
+void MiniExplorerCoimbra::go_to_line(float line_a, float line_b, float line_c,float targetXWorld, float targetYWorld){
+ float lineAngle;
+ float angleError;
+ float linear;
+ float angular;
+
+ //atan2 use the deplacement on X and the deplacement on Y
+ float angleToTarget=atan2(targetYWorld-this->yWorld,targetXWorld-this->xWorld);
+ 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;
+
+ //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(!aligned)
+ lineAngle=atan(-line_a/line_b);
+ else
+ lineAngle=atan(line_a/-line_b);
+ }
+ else{
+ lineAngle=1.5708;
+ }
+
+ //Computing angle error
+ angleError = lineAngle-this->thetaWorld;//TODO that I m not sure
+ angleError = atan(sin(angleError)/cos(angleError));
+
+ //Calculating velocities
+ linear=this->kv*(3.1416);
+ angular=this->kh*angleError;
+
+ float angularLeft=(linear-0.5*this->distanceWheels*angular)/this->radiusWheels;
+ float angularRight=(linear+0.5*this->distanceWheels*angular)/this->radiusWheels;
+
+ //Normalize speed for motors
+ if(abs(angularLeft)>abs(angularRight)) {
+ angularRight=this->speed*abs(angularRight/angularLeft)*this->sign1(angularRight);
+ angularLeft=this->speed*this->sign1(angularLeft);
+ }
+ else {
+ angularLeft=this->speed*abs(angularLeft/angularRight)*this->sign1(angularLeft);
+ angularRight=this->speed*this->sign1(angularRight);
+ }
+ leftMotor(this->sign2(angularLeft),abs(angularLeft));
+ rightMotor(this->sign2(angularRight),abs(angularRight));
+}
+
+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-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);
+ *forceRepulsionComputedX+=this->repulsionConstantForce*probaCell*(xWorldCell-this->xWorld)/pow(distanceCellToRobot,3);
+ *forceRepulsionComputedY+=this->repulsionConstantForce*probaCell*(yWorldCell-this->yWorld)/pow(distanceCellToRobot,3);
+ }
+}
+
+//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;
+}
+
+/*
+void MiniExplorerCoimbra::test_procedure_lab_4(){
+ this->map.fill_map_with_initial();
+ float xEstimatedK=this->xWorld;
+ float yEstimatedK=this->yWorld;
+ float thetaWorldEstimatedK = this->thetaWorld;
+ float distanceMoved;
+ float angleMoved;
+ float PreviousCovarianceOdometricPositionEstimate[3][3];
+ PreviousCovarianceOdometricPositionEstimate[0][0]=0;
+ PreviousCovarianceOdometricPositionEstimate[0][1]=0;
+ PreviousCovarianceOdometricPositionEstimate[0][2]=0;
+ PreviousCovarianceOdometricPositionEstimate[1][0]=0;
+ PreviousCovarianceOdometricPositionEstimate[1][1]=0;
+ PreviousCovarianceOdometricPositionEstimate[1][2]=0;
+ PreviousCovarianceOdometricPositionEstimate[2][0]=0;
+ PreviousCovarianceOdometricPositionEstimate[2][1]=0;
+ PreviousCovarianceOdometricPositionEstimate[2][2]=0;
+ while(1){
+ distanceMoved=50;
+ angleMoved=0;
+ this->go_straight_line(50);
+ wait(1);
+ procedure_lab_4(xEstimatedK,yEstimatedK,thetaWorldEstimatedK,distanceMoved,angleMoved,PreviousCovarianceOdometricPositionEstimate);
+ pc.printf("\n\r x:%f,y:%f,theta:%f",this->xWorld,this->yWorld,this->thetaWorld);
+ pc.printf("\n\r xEstim:%f,yEstim:%f,thetaEstim:%f",xEstimatedK,yEstimatedK,thetaWorldEstimatedK);
+ this->turn_to_target(PI/2);
+ distanceMoved=0;
+ angleMoved=PI/2;
+ procedure_lab_4(xEstimatedK,yEstimatedK,thetaWorldEstimatedK,distanceMoved,angleMoved,PreviousCovarianceOdometricPositionEstimate);
+ pc.printf("\n\r x:%f,y:%f,theta:%f",this->xWorld,this->yWorld,this->thetaWorld);
+ pc.printf("\n\r xEstim:%f,yEstim:%f,thetaEstim:%f",xEstimatedK,yEstimatedK,thetaWorldEstimatedK);
+ }
+}
+
+void MiniExplorerCoimbra::go_straight_line(float distanceCm){
+ leftMotor(1,1);
+ rightMotor(1,1);
+ float xEstimated=this->xWorld+distanceCm*cos(this->thetaWorld);
+ float yEstimated=this->yWorld+distanceCm*sin(this->thetaWorld);
+ while(1){
+ this->myOdometria();
+ if(abs(xEstimated-this->xWorld) < 0.1 && abs(yEstimated-this->yWorld) < 0.1)
+ break;
+ }
+ leftMotor(1,0);
+ rightMotor(1,0);
+}
+
+//compute predicted localisation (assume movements are either straight lines or pure rotation), update PreviousCovarianceOdometricPositionEstimate
+//TODO tweak constant rewritte it good
+void MiniExplorerCoimbra::procedure_lab_4(float xEstimatedK,float yEstimatedK, float thetaWorldEstimatedK, float distanceMoved, float angleMoved, float PreviousCovarianceOdometricPositionEstimate[3][3]){
+
+ float distanceMovedByLeftWheel=distanceMoved/2;
+ float distanceMovedByRightWheel=distanceMoved/2;
+ if(angleMoved !=0){
+ //TODO check that not sure
+ distanceMovedByLeftWheel=-angleMoved/(2*this->distanceWheels);
+ distanceMovedByRightWheel=angleMoved/(2*this->distanceWheels);
+ }else{
+ distanceMovedByLeftWheel=distanceMoved/2;
+ distanceMovedByRightWheel=distanceMoved/2;
+ }
+
+ float xEstimatedKNext=xEstimatedK+distanceMoved*cos(angleMoved);
+ float yEstimatedKNext=yEstimatedK+distanceMoved*sin(angleMoved);
+ float thetaWorldEstimatedKNext=thetaWorldEstimatedK+angleMoved;
+
+ float kRight=0.1;//error constant
+ float kLeft=0.1;//error constant
+ float motionIncrementCovarianceMatrix[2][2];
+ motionIncrementCovarianceMatrix[0][0]=kRight*abs(distanceMovedByRightWheel);
+ motionIncrementCovarianceMatrix[0][1]=0;
+ motionIncrementCovarianceMatrix[1][0]=0;
+ motionIncrementCovarianceMatrix[1][1]=kLeft*abs(distanceMovedByLeftWheel);
+
+ float jacobianFp[3][3];
+ jacobianFp[0][0]=1;
+ jacobianFp[0][1]=0;
+ jacobianFp[0][2]=-distanceMoved*sin(thetaWorldEstimatedK+angleMoved/2);
+ jacobianFp[1][0]=0;
+ jacobianFp[1][1]=1;
+ jacobianFp[1][2]=distanceMoved*cos(thetaWorldEstimatedK+angleMoved/2);;
+ jacobianFp[2][0]=0;
+ jacobianFp[2][1]=0;
+ jacobianFp[2][2]=1;
+
+ float jacobianFpTranspose[3][3];
+ jacobianFpTranspose[0][0]=1;
+ jacobianFpTranspose[0][1]=0;
+ jacobianFpTranspose[0][2]=0;
+ jacobianFpTranspose[1][0]=0;
+ jacobianFpTranspose[1][1]=1;
+ jacobianFpTranspose[1][2]=0;
+ jacobianFpTranspose[2][0]=-distanceMoved*sin(thetaWorldEstimatedK+angleMoved/2);
+ jacobianFpTranspose[2][1]=distanceMoved*cos(thetaWorldEstimatedK+angleMoved/2);
+ jacobianFpTranspose[2][2]=1;
+
+ float jacobianFDeltarl[3][2];
+ jacobianFDeltarl[0][0]=(1/2)*cos(thetaWorldEstimatedK+angleMoved/2)-(distanceMoved/(2*this->distanceWheels))*sin(thetaWorldEstimatedK+angleMoved/2);
+ jacobianFDeltarl[0][1]=(1/2)*cos(thetaWorldEstimatedK+angleMoved/2)+(distanceMoved/(2*this->distanceWheels))*sin(thetaWorldEstimatedK+angleMoved/2);
+ jacobianFDeltarl[1][0]=(1/2)*sin(thetaWorldEstimatedK+angleMoved/2)+(distanceMoved/(2*this->distanceWheels))*cos(thetaWorldEstimatedK+angleMoved/2);
+ jacobianFDeltarl[1][1]=(1/2)*sin(thetaWorldEstimatedK+angleMoved/2)-(distanceMoved/(2*this->distanceWheels))*cos(thetaWorldEstimatedK+angleMoved/2);
+ jacobianFDeltarl[2][0]=1/this->distanceWheels;
+ jacobianFDeltarl[2][1]=-1/this->distanceWheels;
+
+ float jacobianFDeltarlTranspose[2][3];//1,3,5;2,4,6
+ jacobianFDeltarlTranspose[0][0]=(1/2)*cos(thetaWorldEstimatedK+angleMoved/2)-(distanceMoved/(2*this->distanceWheels))*sin(thetaWorldEstimatedK+angleMoved/2);
+ jacobianFDeltarlTranspose[0][1]=(1/2)*sin(thetaWorldEstimatedK+angleMoved/2)+(distanceMoved/(2*this->distanceWheels))*cos(thetaWorldEstimatedK+angleMoved/2);
+ jacobianFDeltarlTranspose[0][2]=1/this->distanceWheels;
+ jacobianFDeltarlTranspose[1][0]=(1/2)*cos(thetaWorldEstimatedK+angleMoved/2)+(distanceMoved/(2*this->distanceWheels))*sin(thetaWorldEstimatedK+angleMoved/2);
+ jacobianFDeltarlTranspose[1][1]=(1/2)*sin(thetaWorldEstimatedK+angleMoved/2)-(distanceMoved/(2*this->distanceWheels))*cos(thetaWorldEstimatedK+angleMoved/2);
+ jacobianFDeltarlTranspose[1][2]=-1/this->distanceWheels;
+
+ float tempMatrix3_3[3][3];
+ int i;
+ int j;
+ int k;
+ for( i = 0; i < 3; ++i){//mult 3*3, 3*3
+ for(j = 0; j < 3; ++j){
+ for(k = 0; k < 3; ++k){
+ tempMatrix3_3[i][j] += jacobianFp[i][k] * PreviousCovarianceOdometricPositionEstimate[k][j];
+ }
+ }
+ }
+ float sndTempMatrix3_3[3][3];
+ for(i = 0; i < 3; ++i){//mult 3*3, 3*3
+ for(j = 0; j < 3; ++j){
+ for(k = 0; k < 3; ++k){
+ sndTempMatrix3_3[i][j] += tempMatrix3_3[i][k] * jacobianFpTranspose[k][j];
+ }
+ }
+ }
+ float tempMatrix3_2[3][2];
+ for(i = 0; i < 3; ++i){//mult 3*2 , 2,2
+ for(j = 0; j < 2; ++j){
+ for(k = 0; k < 2; ++k){
+ tempMatrix3_2[i][j] += jacobianFDeltarl[i][k] * motionIncrementCovarianceMatrix[k][j];
+ }
+ }
+ }
+ float thrdTempMatrix3_3[3][3];
+ for(i = 0; i < 3; ++i){//mult 3*2 , 2,3
+ for(j = 0; j < 3; ++j){
+ for(k = 0; k < 2; ++k){
+ thrdTempMatrix3_3[i][j] += tempMatrix3_2[i][k] * jacobianFDeltarlTranspose[k][j];
+ }
+ }
+ }
+ float newCovarianceOdometricPositionEstimate[3][3];
+ for(i = 0; i < 3; ++i){//add 3*3 , 3*3
+ for(j = 0; j < 3; ++j){
+ newCovarianceOdometricPositionEstimate[i][j]=sndTempMatrix3_3[i][j]+thrdTempMatrix3_3[i][j];
+ }
+ }
+
+ //check measurements from sonars, see if they passed the validation gate
+ float leftCm = get_distance_left_sensor()/10;
+ float frontCm = get_distance_front_sensor()/10;
+ float rightCm = get_distance_right_sensor()/10;
+ //if superior to sonar range, put the value to sonar max range + 1
+ if(leftCm > this->sonarLeft.maxRange)
+ leftCm=this->sonarLeft.maxRange;
+ if(frontCm > this->sonarFront.maxRange)
+ frontCm=this->sonarFront.maxRange;
+ if(rightCm > this->sonarRight.maxRange)
+ rightCm=this->sonarRight.maxRange;
+ //get the estimated measure we should have according to our knowledge of the map and the previously computed localisation
+ float leftCmEstimated=this->sonarLeft.maxRange;
+ float frontCmEstimated=this->sonarFront.maxRange;
+ float rightCmEstimated=this->sonarRight.maxRange;
+ float xWorldCell;
+ float yWorldCell;
+ float currDistance;
+ float xClosestCellLeft;
+ float yClosestCellLeft;
+ float xClosestCellFront;
+ float yClosestCellFront;
+ float xClosestCellRight;
+ float yClosestCellRight;
+ for(int i=0;i<this->map.nbCellWidth;i++){
+ for(int j=0;j<this->map.nbCellHeight;j++){
+ //check if occupied, if not discard
+ if(this->map.get_proba_cell(i,j)==1){
+ //check if in sonar range
+ xWorldCell=this->map.cell_width_coordinate_to_world(i);
+ yWorldCell=this->map.cell_height_coordinate_to_world(j);
+ //check left
+ currDistance=this->sonarLeft.isInRange(xWorldCell,yWorldCell,xEstimatedKNext,yEstimatedKNext,thetaWorldEstimatedKNext);
+ if((currDistance < this->sonarLeft.maxRange) && currDistance!=-1){
+ //check if distance is lower than previous, update lowest if so
+ if(currDistance < leftCmEstimated){
+ leftCmEstimated= currDistance;
+ xClosestCellLeft=xWorldCell;
+ yClosestCellLeft=yWorldCell;
+ }
+ }
+ //check front
+ currDistance=this->sonarFront.isInRange(xWorldCell,yWorldCell,xEstimatedKNext,yEstimatedKNext,thetaWorldEstimatedKNext);
+ if((currDistance < this->sonarFront.maxRange) && currDistance!=-1){
+ //check if distance is lower than previous, update lowest if so
+ if(currDistance < frontCmEstimated){
+ frontCmEstimated= currDistance;
+ xClosestCellFront=xWorldCell;
+ yClosestCellFront=yWorldCell;
+ }
+ }
+ //check right
+ currDistance=this->sonarRight.isInRange(xWorldCell,yWorldCell,xEstimatedKNext,yEstimatedKNext,thetaWorldEstimatedKNext);
+ if((currDistance < this->sonarRight.maxRange) && currDistance!=-1){
+ //check if distance is lower than previous, update lowest if so
+ if(currDistance < rightCmEstimated){
+ rightCmEstimated= currDistance;
+ xClosestCellRight=xWorldCell;
+ yClosestCellRight=yWorldCell;
+ }
+ }
+ }
+ }
+ }
+ //get the innoncation: the value of the difference between the actual measure and what we anticipated
+ float innovationLeft=leftCm-leftCmEstimated;
+ float innovationFront=frontCm-frontCmEstimated;
+ float innovationRight=-rightCm-rightCmEstimated;
+ //compute jacobian of observation
+ float jacobianOfObservationLeft[3];
+ float jacobianOfObservationRight[3];
+ float jacobianOfObservationFront[3];
+ float xSonarLeft=xEstimatedKNext+this->sonarLeft.distanceX;
+ float ySonarLeft=yEstimatedKNext+this->sonarLeft.distanceY;
+ //left
+ jacobianOfObservationLeft[0]=(xSonarLeft-xClosestCellLeft)/leftCmEstimated;
+ jacobianOfObservationLeft[1]=(ySonarLeft-yClosestCellLeft)/leftCmEstimated;
+ jacobianOfObservationLeft[2]=(xClosestCellLeft-xSonarLeft)*(xSonarLeft*sin(thetaWorldEstimatedKNext)+ySonarLeft*cos(thetaWorldEstimatedKNext))+(yClosestCellLeft-ySonarLeft)*(-xSonarLeft*cos(thetaWorldEstimatedKNext)+ySonarLeft*sin(thetaWorldEstimatedKNext));
+ //front
+ float xSonarFront=xEstimatedKNext+this->sonarFront.distanceX;
+ float ySonarFront=yEstimatedKNext+this->sonarFront.distanceY;
+ jacobianOfObservationFront[0]=(xSonarFront-xClosestCellFront)/frontCmEstimated;
+ jacobianOfObservationFront[1]=(ySonarFront-yClosestCellFront)/frontCmEstimated;
+ jacobianOfObservationFront[2]=(xClosestCellFront-xSonarFront)*(xSonarFront*sin(thetaWorldEstimatedKNext)+ySonarFront*cos(thetaWorldEstimatedKNext))+(yClosestCellFront-ySonarFront)*(-xSonarFront*cos(thetaWorldEstimatedKNext)+ySonarFront*sin(thetaWorldEstimatedKNext));
+ //right
+ float xSonarRight=xEstimatedKNext+this->sonarRight.distanceX;
+ float ySonarRight=yEstimatedKNext+this->sonarRight.distanceY;
+ jacobianOfObservationRight[0]=(xSonarRight-xClosestCellRight)/rightCmEstimated;
+ jacobianOfObservationRight[1]=(ySonarRight-yClosestCellRight)/rightCmEstimated;
+ jacobianOfObservationRight[2]=(xClosestCellRight-xSonarRight)*(xSonarRight*sin(thetaWorldEstimatedKNext)+ySonarRight*cos(thetaWorldEstimatedKNext))+(yClosestCellRight-ySonarRight)*(-xSonarRight*cos(thetaWorldEstimatedKNext)+ySonarRight*sin(thetaWorldEstimatedKNext));
+
+ //left
+ float TempMatrix3_3InnovationLeft[3];
+ TempMatrix3_3InnovationLeft[0]=jacobianOfObservationLeft[0]*newCovarianceOdometricPositionEstimate[0][0]+jacobianOfObservationLeft[1]*newCovarianceOdometricPositionEstimate[1][0]+jacobianOfObservationLeft[2]*newCovarianceOdometricPositionEstimate[2][0];
+ TempMatrix3_3InnovationLeft[1]=jacobianOfObservationLeft[0]*newCovarianceOdometricPositionEstimate[0][1]+jacobianOfObservationLeft[1]*newCovarianceOdometricPositionEstimate[1][1]+jacobianOfObservationLeft[2]*newCovarianceOdometricPositionEstimate[2][1];
+ TempMatrix3_3InnovationLeft[2]=jacobianOfObservationLeft[0]*newCovarianceOdometricPositionEstimate[0][2]+jacobianOfObservationLeft[1]*newCovarianceOdometricPositionEstimate[1][2]+jacobianOfObservationLeft[2]*newCovarianceOdometricPositionEstimate[2][2];
+ float innovationConvarianceLeft=TempMatrix3_3InnovationLeft[0]*jacobianOfObservationLeft[0]+TempMatrix3_3InnovationLeft[1]*jacobianOfObservationLeft[1]+TempMatrix3_3InnovationLeft[2]*jacobianOfObservationLeft[2];
+ //front
+ float TempMatrix3_3InnovationFront[3];
+ TempMatrix3_3InnovationFront[0]=jacobianOfObservationFront[0]*newCovarianceOdometricPositionEstimate[0][0]+jacobianOfObservationFront[1]*newCovarianceOdometricPositionEstimate[1][0]+jacobianOfObservationFront[2]*newCovarianceOdometricPositionEstimate[2][0];
+ TempMatrix3_3InnovationFront[1]=jacobianOfObservationFront[0]*newCovarianceOdometricPositionEstimate[0][1]+jacobianOfObservationFront[1]*newCovarianceOdometricPositionEstimate[1][1]+jacobianOfObservationFront[2]*newCovarianceOdometricPositionEstimate[2][1];
+ TempMatrix3_3InnovationFront[2]=jacobianOfObservationFront[0]*newCovarianceOdometricPositionEstimate[0][2]+jacobianOfObservationFront[1]*newCovarianceOdometricPositionEstimate[1][2]+jacobianOfObservationFront[2]*newCovarianceOdometricPositionEstimate[2][2];
+ float innovationConvarianceFront=TempMatrix3_3InnovationFront[0]*jacobianOfObservationFront[0]+TempMatrix3_3InnovationFront[1]*jacobianOfObservationFront[1]+TempMatrix3_3InnovationFront[2]*jacobianOfObservationFront[2];
+ //right
+ float TempMatrix3_3InnovationRight[3];
+ TempMatrix3_3InnovationRight[0]=jacobianOfObservationRight[0]*newCovarianceOdometricPositionEstimate[0][0]+jacobianOfObservationRight[1]*newCovarianceOdometricPositionEstimate[1][0]+jacobianOfObservationRight[2]*newCovarianceOdometricPositionEstimate[2][0];
+ TempMatrix3_3InnovationRight[1]=jacobianOfObservationRight[0]*newCovarianceOdometricPositionEstimate[0][1]+jacobianOfObservationRight[1]*newCovarianceOdometricPositionEstimate[1][1]+jacobianOfObservationRight[2]*newCovarianceOdometricPositionEstimate[2][1];
+ TempMatrix3_3InnovationRight[2]=jacobianOfObservationRight[0]*newCovarianceOdometricPositionEstimate[0][2]+jacobianOfObservationRight[1]*newCovarianceOdometricPositionEstimate[1][2]+jacobianOfObservationRight[2]*newCovarianceOdometricPositionEstimate[2][2];
+ float innovationConvarianceRight=TempMatrix3_3InnovationRight[0]*jacobianOfObservationRight[0]+TempMatrix3_3InnovationRight[1]*jacobianOfObservationRight[1]+TempMatrix3_3InnovationRight[2]*jacobianOfObservationRight[2];
+
+ //check if it pass the validation gate
+ float gateScoreLeft=innovationLeft*innovationLeft/innovationConvarianceLeft;
+ float gateScoreFront=innovationFront*innovationFront/innovationConvarianceFront;
+ float gateScoreRight=innovationRight*innovationRight/innovationConvarianceRight;
+ int leftPassed=0;
+ int frontPassed=0;
+ int rightPassed=0;
+ int e=10;//constant
+ if(gateScoreLeft < e)
+ leftPassed=1;
+ if(gateScoreFront < e)
+ frontPassed=10;
+ if(gateScoreRight < e)
+ rightPassed=100;
+ //for those who passed
+ //compute composite innovation
+ float compositeInnovation[3];
+ int nbPassed=leftPassed+frontPassed+rightPassed;
+ switch(nbPassed){
+ case 0://none
+ compositeInnovation[0]=0;
+ compositeInnovation[1]=0;
+ compositeInnovation[2]=0;
+ break;
+ case 1://left
+ compositeInnovation[0]=innovationLeft;
+ compositeInnovation[1]=0;
+ compositeInnovation[2]=0;
+ break;
+ case 10://front
+ compositeInnovation[0]=0;
+ compositeInnovation[1]=innovationFront;
+ compositeInnovation[2]=0;
+ break;
+ case 11://left and front
+ compositeInnovation[0]=innovationLeft;
+ compositeInnovation[1]=innovationFront;
+ compositeInnovation[2]=0;
+ break;
+ case 100://right
+ compositeInnovation[0]=0;
+ compositeInnovation[1]=0;
+ compositeInnovation[2]=innovationRight;
+ break;
+ case 101://right and left
+ compositeInnovation[0]=innovationLeft;
+ compositeInnovation[1]=0;
+ compositeInnovation[2]=innovationRight;
+ break;
+ case 110://right and front
+ compositeInnovation[0]=0;
+ compositeInnovation[1]=innovationFront;
+ compositeInnovation[2]=innovationRight;
+ break;
+ case 111://right front and left
+ compositeInnovation[0]=innovationLeft;
+ compositeInnovation[1]=innovationFront;
+ compositeInnovation[2]=innovationRight;
+ break;
+ }
+ //compute composite measurement Jacobian
+ float *compositeMeasurementJacobian;
+ switch(nbPassed){
+ case 0://none
+ break;
+ case 1://left
+ //compositeMeasurementJacobian = jacobianOfObservationLeft
+ break;
+ case 10://front
+ //compositeMeasurementJacobian = jacobianOfObservationFront
+ break;
+ case 11://left and front
+ compositeMeasurementJacobian=new float[6];
+ compositeMeasurementJacobian[0]= jacobianOfObservationLeft[0];
+ compositeMeasurementJacobian[1]= jacobianOfObservationLeft[1];
+ compositeMeasurementJacobian[2]= jacobianOfObservationLeft[2];
+ compositeMeasurementJacobian[3]= jacobianOfObservationFront[0];
+ compositeMeasurementJacobian[4]= jacobianOfObservationFront[1];
+ compositeMeasurementJacobian[5]= jacobianOfObservationFront[2];
+ break;
+ case 100://right
+ //compositeMeasurementJacobian = jacobianOfObservationRight
+ break;
+ case 101://right and left
+ compositeMeasurementJacobian=new float[6];
+ compositeMeasurementJacobian[0]= jacobianOfObservationLeft[0];
+ compositeMeasurementJacobian[1]= jacobianOfObservationLeft[1];
+ compositeMeasurementJacobian[2]= jacobianOfObservationLeft[2];
+ compositeMeasurementJacobian[3]= jacobianOfObservationRight[0];
+ compositeMeasurementJacobian[4]= jacobianOfObservationRight[1];
+ compositeMeasurementJacobian[5]= jacobianOfObservationRight[2];
+
+ break;
+ case 110://right and front
+ compositeMeasurementJacobian=new float[6];
+ compositeMeasurementJacobian[0]= jacobianOfObservationFront[0];
+ compositeMeasurementJacobian[1]= jacobianOfObservationFront[1];
+ compositeMeasurementJacobian[2]= jacobianOfObservationFront[2];
+ compositeMeasurementJacobian[3]= jacobianOfObservationRight[0];
+ compositeMeasurementJacobian[4]= jacobianOfObservationRight[1];
+ compositeMeasurementJacobian[5]= jacobianOfObservationRight[2];
+
+ break;
+ case 111://right front and left
+ compositeMeasurementJacobian=new float[9];
+ compositeMeasurementJacobian[0]= jacobianOfObservationLeft[0];
+ compositeMeasurementJacobian[1]= jacobianOfObservationLeft[1];
+ compositeMeasurementJacobian[2]= jacobianOfObservationLeft[2];
+ compositeMeasurementJacobian[3]= jacobianOfObservationFront[0];
+ compositeMeasurementJacobian[4]= jacobianOfObservationFront[1];
+ compositeMeasurementJacobian[5]= jacobianOfObservationFront[2];
+ compositeMeasurementJacobian[6]= jacobianOfObservationRight[0];
+ compositeMeasurementJacobian[7]= jacobianOfObservationRight[1];
+ compositeMeasurementJacobian[8]= jacobianOfObservationRight[2];
+ break;
+ }
+ //compute composite innovation covariance TODO dont have time, I assume you can just multiply them, can also simply all this easily
+ float compositeInnovationCovariance;
+ switch(nbPassed){
+ case 0://none
+ compositeInnovationCovariance=1;
+ break;
+ case 1://left
+ compositeInnovationCovariance = innovationConvarianceLeft;
+
+ break;
+ case 10://front
+ compositeInnovationCovariance = innovationConvarianceFront;
+ break;
+ case 11://left and front
+ compositeInnovationCovariance=innovationConvarianceLeft*innovationConvarianceFront;
+
+ break;
+ case 100://right
+ compositeInnovationCovariance = innovationConvarianceRight;
+ break;
+ case 101://right and left
+ compositeInnovationCovariance=innovationConvarianceLeft*innovationConvarianceRight;
+ break;
+ case 110://right and front
+ compositeInnovationCovariance=innovationConvarianceFront*innovationConvarianceRight;
+
+
+ break;
+ case 111://right front and left
+ compositeInnovationCovariance=innovationConvarianceLeft*innovationConvarianceFront*innovationConvarianceRight;
+
+ break;
+ }
+
+ //compute kalman gain
+ float kalmanGain[3][3];
+ switch(nbPassed){
+ //mult nbSonarPassed*3 , 3*3
+ case 0://none
+ break;
+ case 1://left
+
+ for(i = 0; i < 3; ++i){//mult 3*3, 3*1
+ for(j = 0; j < 1; ++j){
+ for(k = 0; k < 3; ++k){
+ kalmanGain[i][j] += newCovarianceOdometricPositionEstimate[i][k] * compositeInnovationCovariance[k];
+ }
+ }
+ }
+
+ break;
+ case 10://front
+ for(i = 0; i < 3; ++i){//mult 3*3, 3*1
+ for(j = 0; j < 1; ++j){
+ for(k = 0; k < 3; ++k){
+ kalmanGain[i][j] += newCovarianceOdometricPositionEstimate[i][k] * compositeInnovationCovariance[k];
+ }
+ }
+ }
+ break;
+ case 11://left and front
+ for(i = 0; i < 3; ++i){//mult 3*3, 3*2
+ for(j = 0; j < 2; ++j){
+ for(k = 0; k < 3; ++k){
+ kalmanGain[i][j] += newCovarianceOdometricPositionEstimate[i][k] * compositeInnovationCovariance[k+j*3];
+ }
+ }
+ }
+
+ break;
+ case 100://right
+ for(i = 0; i < 3; ++i){//mult 3*3, 3*1
+ for(j = 0; j < 1; ++j){
+ for(k = 0; k < 3; ++k){
+ kalmanGain[i][j] += newCovarianceOdometricPositionEstimate[i][k] * compositeInnovationCovariance[k];
+ }
+ }
+ }
+ break;
+ case 101://right and left
+ for(i = 0; i < 3; ++i){//mult 3*3, 3*2
+ for(j = 0; j < 2; ++j){
+ for(k = 0; k < 3; ++k){
+ kalmanGain[i][j] += newCovarianceOdometricPositionEstimate[i][k] * compositeInnovationCovariance[k+j*3];
+ }
+ }
+ }
+
+ break;
+ case 110://right and front
+ for(i = 0; i < 3; ++i){//mult 3*3, 3*2
+ for(j = 0; j < 2; ++j){
+ for(k = 0; k < 3; ++k){
+ kalmanGain[i][j] += newCovarianceOdometricPositionEstimate[i][k] * compositeInnovationCovariance[k+j*3];
+ }
+ }
+ }
+
+
+ break;
+ case 111://right front and left
+ for(i = 0; i < 3; ++i){//mult 3*3, 3*3
+ for(j = 0; j < 3; ++j){
+ for(k = 0; k < 3; ++k){
+ kalmanGain[i][j] += newCovarianceOdometricPositionEstimate[i][k] * compositeInnovationCovariance[k+j*3];
+ }
+ }
+ }
+
+ break;
+ }
+
+ for(i = 0; i < 3; ++i){//mult 3*3, 3*3
+ for(j = 0; j < 3; ++j){
+ kalmanGain[i][j] = kalmanGain[i][j]/compositeInnovationCovariance;
+ }
+ }
+ //compute kalman gain * composite innovation
+ //mult 3*3 , 3*1
+ float result3_1[3];
+ for(i = 0; i < 3; ++i){//mult 3*3, 3*1
+ for(k = 0; k < 3; ++k){
+ result3_1[i] += kalmanGain[i][k] * compositeInnovation[k];
+ }
+ }
+ //compute updated robot position estimate
+ float xEstimatedKLast=xEstimatedKNext+result3_1[0];
+ float yEstimatedKLast=yEstimatedKNext+result3_1[1];
+ float thetaWorldEstimatedKLast=thetaWorldEstimatedKNext+result3_1[2];
+ //store the resultant covariance for next estimation
+
+ float kalmanGainTranspose[3][3];
+ kalmanGainTranspose[0][0]=kalmanGain[0][0];
+ kalmanGainTranspose[0][1]=kalmanGain[1][0];
+ kalmanGainTranspose[0][2]=kalmanGain[2][0];
+ kalmanGainTranspose[1][0]=kalmanGain[0][1];
+ kalmanGainTranspose[1][1]=kalmanGain[1][1];
+ kalmanGainTranspose[1][2]=kalmanGain[2][1];
+ kalmanGainTranspose[2][0]=kalmanGain[0][2];
+ kalmanGainTranspose[2][1]=kalmanGain[1][2];
+ kalmanGainTranspose[2][2]=kalmanGain[2][2];
+
+ //mult 3*3 , 3*3
+ float fithTempMatrix3_3[3][3];
+ for(i = 0; i < 3; ++i){//mult 3*3 , 3*3
+ for(j = 0; j < 3; ++j){
+ for(k = 0; k < 3; ++k){
+ fithTempMatrix3_3[i][j] += kalmanGain[i][k] * kalmanGainTranspose[k][j];
+ }
+ }
+ }
+ for(i = 0; i < 3; ++i){//add 3*3 , 3*3
+ for(j = 0; j < 3; ++j){
+ fithTempMatrix3_3[i][j]=fithTempMatrix3_3[i][j]*compositeInnovationCovariance;
+ }
+ }
+ float covariancePositionEsimatedLast[3][3];
+ for(i = 0; i < 3; ++i){//add 3*3 , 3*3
+ for(j = 0; j < 3; ++j){
+ covariancePositionEsimatedLast[i][j]=fithTempMatrix3_3[i][j]+newCovarianceOdometricPositionEstimate[i][j];
+ }
+ }
+ //update PreviousCovarianceOdometricPositionEstimate
+ for(i = 0; i < 3; ++i){
+ for(j = 0; j < 3; ++j){
+ PreviousCovarianceOdometricPositionEstimate[i][j]=covariancePositionEsimatedLast[i][j];
+ }
+ }
+
+ xEstimatedK=xEstimatedKLast;
+ yEstimatedK=yEstimatedKLast;
+ thetaWorldEstimatedK=thetaWorldEstimatedKLast;
+}
+*/
\ No newline at end of file
diff -r 000000000000 -r 9f7ee7ed13e4 MiniExplorerCoimbra.hpp
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/MiniExplorerCoimbra.hpp Mon Jun 26 12:05:20 2017 +0000
@@ -0,0 +1,107 @@
+#ifndef MINIEXPLORERCOIMBRA_HPP
+#define MINIEXPLORERCOIMBRA_HPP
+
+#include "Map.hpp"
+#include "Sonar.hpp"
+#include<math.h>
+
+ /*
+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;
+ Sonar sonarRight;
+ float speed;
+ float radiusWheels;
+ float distanceWheels;
+ float khro;
+ float ka;
+ float kb;
+ float kv;
+ float kh;
+
+ float rangeForce;
+ float attractionConstantForce;
+ float repulsionConstantForce;
+
+ MiniExplorerCoimbra(float defaultXWorld, float defaultYWorld, float defaultThetaWorld);
+
+ //generate a position randomly and makes the robot go there while updating the map
+ void randomize_and_map();
+
+ //move of targetXWorld and targetYWorld ending in a targetAngleWorld
+ void go_to_point_with_angle(float targetXWorld, float targetYWorld, float targetAngleWorld);
+
+ //use virtual force field
+ void try_to_reach_target(float targetXWorld,float targetYWorld);
+
+
+ void test_procedure_lab_4();
+
+ private:
+
+ void myOdometria();
+
+ void setXYThetaAndXYThetaWorld(float defaultXWorld, float defaultYWorld, float defaultThetaWorld);
+
+ float update_angular_speed_wheels_go_to_point_with_angle(float targetXWorld, float targetYWorld, float targetAngleWorld, float dt);
+
+ void update_sonar_values(float leftMm,float frontMm,float rightMm);
+
+ void do_half_flip();
+
+ //Distance computation function
+ float dist(float x1, float y1, float x2, float y2);
+
+ /*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 turn_to_target(float angleToTarget);
+
+ void print_map_with_robot_position_and_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* forceXWorld, float* forceYWorld, float targetXWorld, float targetYWorld);
+
+ 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);
+
+ void update_force(int widthIndice, int heightIndice, float* forceRepulsionComputedX, float* forceRepulsionComputedY );
+
+ //return 1 if positiv, -1 if negativ
+ float sign1(float value);
+
+ //return 1 if positiv, 0 if negativ
+ int sign2(float value);
+
+ void go_straight_line(float distanceCm);
+
+ void procedure_lab_4(float xEstimatedK,float yEstimatedK, float thetaWorldEstimatedK, float distanceMoved, float angleMoved, float PreviousCovarianceOdometricPositionEstimate[3][3]);
+
+};
+
+
+#endif
+
diff -r 000000000000 -r 9f7ee7ed13e4 Sonar.cpp
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/Sonar.cpp Mon Jun 26 12:05:20 2017 +0000
@@ -0,0 +1,129 @@
+#include "Sonar.hpp"
+
+#define PI 3.14159
+
+Sonar::Sonar(float angleFromCenter, float distanceXFromRobotCenter, float distanceYFromRobotCenter ){
+ this->angleFromCenter=angleFromCenter;
+ this->distanceX=distanceXFromRobotCenter;
+ this->distanceY=distanceYFromRobotCenter;
+ this->maxRange=50;//cm
+ this->minRange=10;//Rmin cm
+ this->incertitudeRange=10;//cm
+ this->angleRange=3.14159/3;//Omega rad
+}
+
+//return distance sonar to cell if in range, -1 if not
+float Sonar::isInRange(float xCell, float yCell, float xRobotWorld, float yRobotWorld, float thetaWorld){
+ float xSonar=xRobotWorld+this->distanceX;
+ float ySonar=yRobotWorld+this->distanceY;
+ float distanceCellToSonar=sqrt(pow(xCell-xSonar,2)+pow(yCell-ySonar,2));
+
+ //check if the distance between the cell and the robot is within the circle of range RADIUS_WHEELS
+ if( distanceCellToSonar < this->maxRange){
+ //float anglePointToSonar=this->compute_angle_between_vectors(xCell,yCell,xSonar,ySonar);//angle beetween the point and the sonar beam
+ float angleCellToSonar=atan2(yCell-yRobotWorld,xCell-xRobotWorld);//like world system
+
+ float angleOriginToMidleOfBeam=thetaWorld+this->angleFromCenter;//
+
+ float angleDifference=angleCellToSonar-angleOriginToMidleOfBeam;
+ if(angleDifference > PI)
+ angleDifference=angleDifference-2*PI;
+ if(angleDifference < -PI)
+ angleDifference=angleDifference+2*PI;
+ //check if absolute difference between the angles is no more than Omega/2
+ if(angleDifference > 0 && angleDifference <= this->angleRange/2 ||angleDifference < 0 && angleDifference >= -this->angleRange/2 ){
+ return distanceCellToSonar;
+ }
+ }
+ return -1;
+}
+
+//function that check if a cell A(x,y) is in the range of the front sonar S(xs,ys) (with an angle depending on the sonar used, front 0, left PI/3, right -PI/3) returns the probability it's occuPIed/empty [0;1]
+float Sonar::compute_probability_t(float distanceObstacleDetected, float xCell, float yCell, float xRobotWorld, float yRobotWorld, float thetaWorld){
+ float xSonar=xRobotWorld+this->distanceX;
+ float ySonar=yRobotWorld+this->distanceY;
+ float distancePointToSonar=sqrt(pow(xCell-xSonar,2)+pow(yCell-ySonar,2));
+ //check if the distance between the cell and the robot is within the circle of range RADIUS_WHEELS
+ if( distancePointToSonar < this->maxRange){
+ //float anglePointToSonar=this->compute_angle_between_vectors(xCell,yCell,xSonar,ySonar);//angle beetween the point and the sonar beam
+ float anglePointToSonar=atan2(yCell-yRobotWorld,xCell-xRobotWorld);//like world system
+
+ float angleOriginToMidleOfBeam=thetaWorld+this->angleFromCenter;//
+
+ float angleDifference=anglePointToSonar-angleOriginToMidleOfBeam;
+ if(angleDifference > PI)
+ angleDifference=angleDifference-2*PI;
+ if(angleDifference < -PI)
+ angleDifference=angleDifference+2*PI;
+ //check if absolute difference between the angles is no more than Omega/2
+ if(angleDifference > 0 && angleDifference <= this->angleRange/2 ||angleDifference < 0 && angleDifference >= -this->angleRange/2 ){
+
+ if( distancePointToSonar < (distanceObstacleDetected - this->incertitudeRange)){
+ //point before obstacle, probably empty
+ /*****************************************************************************/
+ float Ea=1.f-pow((2*angleDifference)/this->angleRange,2);
+ float Er;
+ if(distancePointToSonar < this->minRange){
+ //point before minimum sonar range
+ Er=0.f;
+ }else{
+ //point after minimum sonar range
+ Er=1.f-pow((distancePointToSonar-this->minRange)/(distanceObstacleDetected-this->incertitudeRange-this->minRange),2);
+ }
+ /*****************************************************************************/
+ //if((1.f-Er*Ea)/2.f >1 || (1.f-Er*Ea)/2.f < 0)
+ // pc.printf("\n\r return value=%f,Er=%f,Ea=%f,angleDifference=%f",(1.f-Er*Ea)/2.f,Er,Ea,angleDifference);
+ return (1.f-Er*Ea)/2.f;
+ }else{
+ //probably occuPIed
+ /*****************************************************************************/
+ float Oa=1.f-pow((2*angleDifference)/this->angleRange,2);
+ float Or;
+ if( distancePointToSonar <= (distanceObstacleDetected + this->incertitudeRange)){
+ //point between distanceObstacleDetected +- INCERTITUDE_SONAR
+ Or=1-pow((distancePointToSonar-distanceObstacleDetected)/(this->incertitudeRange),2);
+ }else{
+ //point after in range of the sonar but after the zone detected
+ Or=0;
+ }
+ /*****************************************************************************/
+ //if((1+Or*Oa)/2 >1 || (1+Or*Oa)/2 < 0)
+ // pc.printf("\n\r return value=%f,Er=%f,Ea=%f,angleDifference=%f",(1+Or*Oa)/2,Or,Oa,angleDifference);
+ return (1+Or*Oa)/2;
+ }
+ }
+ }
+ //not checked by the sonar
+ return 0.5;
+}
+
+//returns the angle between the vectors (x,y) and (xs,ys)
+float Sonar::compute_angle_between_vectors(float x, float y,float xs,float ys){
+ //alpha angle between ->x and ->SA
+ //vector S to A ->SA
+ float vSAx=x-xs;
+ float vSAy=y-ys;
+ //norme SA
+ float normeSA=sqrt(pow(vSAx,2)+pow(vSAy,2));
+ //vector ->x (1,0)
+ float cosAlpha=1*vSAy/*+0*vSAx*//normeSA;;
+ //vector ->y (0,1)
+ float sinAlpha=/*0*vSAy+*/1*vSAx/normeSA;//+0*vSAx;
+ if (sinAlpha < 0)
+ return -acos(cosAlpha);
+ else
+ return acos(cosAlpha);
+}
+
+//makes the angle inAngle between 0 and 2PI
+float Sonar::rad_angle_check(float inAngle){
+ if(inAngle > 0){
+ while(inAngle > (2*PI))
+ inAngle-=2*PI;
+ }else{
+ while(inAngle < 0)
+ inAngle+=2*PI;
+ }
+ return inAngle;
+}
+
diff -r 000000000000 -r 9f7ee7ed13e4 Sonar.hpp
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/Sonar.hpp Mon Jun 26 12:05:20 2017 +0000
@@ -0,0 +1,36 @@
+#ifndef SONAR_HPP
+#define SONAR_HPP
+
+#include<math.h>
+
+class Sonar {
+
+ public:
+ float maxRange;//cm
+ float minRange;//Rmin cm
+ float incertitudeRange;//cm
+ float angleRange;//Omega rad
+ float angleFromCenter;
+ float distanceX;
+ float distanceY;
+
+ //the distance are in the world coordinates
+ Sonar(float angleFromCenter, float distanceXFromRobotCenter, float distanceYFromRobotCenter );
+
+ float compute_probability_t(float distanceObstacleDetected, float xCell, float yCell, float xRobotWorld, float yRobotWorld, float theta);
+
+ //return distance sonar to cell if in range, -1 if not
+ float isInRange(float xCell, float yCell, float xRobotWorld, float yRobotWorld, float thetaWorld);
+
+ private:
+
+ //returns the angle between the vectors (x,y) and (xs,ys)
+ float compute_angle_between_vectors(float x, float y,float xs,float ys);
+
+ //makes the angle inAngle between 0 and 2pi
+ float rad_angle_check(float inAngle);
+
+};
+
+#endif
+
diff -r 000000000000 -r 9f7ee7ed13e4 main.cpp
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/main.cpp Mon Jun 26 12:05:20 2017 +0000
@@ -0,0 +1,11 @@
+#include "MiniExplorerCoimbra.hpp"
+
+int main(){
+ MiniExplorerCoimbra myRobot(0,0,0);
+ //test lab2
+ //myRobot.randomize_and_map();
+ //test lab3
+ //myRobot.try_to_reach_target(50,30);
+ return 0;
+}
+
diff -r 000000000000 -r 9f7ee7ed13e4 mbed.bld --- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed.bld Mon Jun 26 12:05:20 2017 +0000 @@ -0,0 +1,1 @@ +https://mbed.org/users/mbed_official/code/mbed/builds/64910690c574 \ No newline at end of file