test morning
Dependencies: ISR_Mini-explorer mbed
Fork of roboticLab_withclass_3_July by
MiniExplorerCoimbra.cpp@13:b0ddd71e8f08, 2017-07-12 (annotated)
- Committer:
- Ludwigfr
- Date:
- Wed Jul 12 09:07:31 2017 +0000
- Revision:
- 13:b0ddd71e8f08
- Parent:
- 12:1e80471c5c6c
- Child:
- 14:696187e74411
12/07 9:07;
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
Ludwigfr | 0:9f7ee7ed13e4 | 1 | #include "MiniExplorerCoimbra.hpp" |
Ludwigfr | 0:9f7ee7ed13e4 | 2 | #include "robot.h" |
Ludwigfr | 0:9f7ee7ed13e4 | 3 | |
Ludwigfr | 0:9f7ee7ed13e4 | 4 | #define PI 3.14159 |
Ludwigfr | 0:9f7ee7ed13e4 | 5 | |
Ludwigfr | 9:1cc27f33d3e1 | 6 | MiniExplorerCoimbra::MiniExplorerCoimbra(float defaultXWorld, float defaultYWorld, float defaultThetaWorld, float widthRealMap, float heightRealMap):map(widthRealMap,heightRealMap,12,8),sonarLeft(10*PI/36,-4,4),sonarFront(0,0,5),sonarRight(-10*PI/36,4,4),covariancePositionEstimationK(3,3){ |
Ludwigfr | 0:9f7ee7ed13e4 | 7 | i2c1.frequency(100000); |
Ludwigfr | 0:9f7ee7ed13e4 | 8 | initRobot(); //Initializing the robot |
Ludwigfr | 0:9f7ee7ed13e4 | 9 | pc.baud(9600); // baud for the pc communication |
Ludwigfr | 0:9f7ee7ed13e4 | 10 | |
Ludwigfr | 0:9f7ee7ed13e4 | 11 | measure_always_on();//TODO check if needed |
Ludwigfr | 0:9f7ee7ed13e4 | 12 | |
Ludwigfr | 0:9f7ee7ed13e4 | 13 | this->setXYThetaAndXYThetaWorld(defaultXWorld,defaultYWorld,defaultThetaWorld); |
Ludwigfr | 0:9f7ee7ed13e4 | 14 | this->radiusWheels=3.25; |
Ludwigfr | 0:9f7ee7ed13e4 | 15 | this->distanceWheels=7.2; |
Ludwigfr | 0:9f7ee7ed13e4 | 16 | |
Ludwigfr | 8:072a76960e27 | 17 | //go to point |
geotsam | 1:20f48907c726 | 18 | this->k_linear=10; |
geotsam | 1:20f48907c726 | 19 | this->k_angular=200; |
Ludwigfr | 8:072a76960e27 | 20 | |
Ludwigfr | 8:072a76960e27 | 21 | //go to point with angle |
Ludwigfr | 8:072a76960e27 | 22 | this->khro=0.3; |
Ludwigfr | 8:072a76960e27 | 23 | this->ka=0.8; |
Ludwigfr | 8:072a76960e27 | 24 | this->kb=-0.36; |
Ludwigfr | 8:072a76960e27 | 25 | this->kv=200;//velocity |
Ludwigfr | 8:072a76960e27 | 26 | |
Ludwigfr | 8:072a76960e27 | 27 | //go to line kh > 0, kd > 0 (200,5), dont turn to line enough, (10,10) turn on itself, |
Ludwigfr | 8:072a76960e27 | 28 | this->kh=650; |
Ludwigfr | 8:072a76960e27 | 29 | this->kd=10;//previous 5 |
Ludwigfr | 8:072a76960e27 | 30 | |
geotsam | 1:20f48907c726 | 31 | this->speed=300; |
Ludwigfr | 0:9f7ee7ed13e4 | 32 | |
Ludwigfr | 3:37345c109dfc | 33 | this->rangeForce=50; |
Ludwigfr | 8:072a76960e27 | 34 | this->attractionConstantForce=1; |
Ludwigfr | 9:1cc27f33d3e1 | 35 | //-90 ok with attraction impacted by distance |
Ludwigfr | 9:1cc27f33d3e1 | 36 | this->repulsionConstantForce=-90; |
Ludwigfr | 5:19f24c363418 | 37 | |
Ludwigfr | 0:9f7ee7ed13e4 | 38 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 39 | |
Ludwigfr | 0:9f7ee7ed13e4 | 40 | void MiniExplorerCoimbra::setXYThetaAndXYThetaWorld(float defaultXWorld, float defaultYWorld, float defaultThetaWorld){ |
Ludwigfr | 0:9f7ee7ed13e4 | 41 | this->xWorld=defaultXWorld; |
Ludwigfr | 0:9f7ee7ed13e4 | 42 | this->yWorld=defaultYWorld; |
Ludwigfr | 0:9f7ee7ed13e4 | 43 | this->thetaWorld=defaultThetaWorld; |
Ludwigfr | 0:9f7ee7ed13e4 | 44 | X=defaultYWorld; |
Ludwigfr | 0:9f7ee7ed13e4 | 45 | Y=-defaultXWorld; |
Ludwigfr | 0:9f7ee7ed13e4 | 46 | if(defaultThetaWorld < -PI/2) |
Ludwigfr | 0:9f7ee7ed13e4 | 47 | theta=PI/2+PI-defaultThetaWorld; |
Ludwigfr | 0:9f7ee7ed13e4 | 48 | else |
Ludwigfr | 0:9f7ee7ed13e4 | 49 | theta=defaultThetaWorld-PI/2; |
Ludwigfr | 0:9f7ee7ed13e4 | 50 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 51 | |
Ludwigfr | 0:9f7ee7ed13e4 | 52 | void MiniExplorerCoimbra::myOdometria(){ |
Ludwigfr | 0:9f7ee7ed13e4 | 53 | Odometria(); |
Ludwigfr | 0:9f7ee7ed13e4 | 54 | this->xWorld=-Y; |
Ludwigfr | 0:9f7ee7ed13e4 | 55 | this->yWorld=X; |
Ludwigfr | 0:9f7ee7ed13e4 | 56 | if(theta >PI/2) |
Ludwigfr | 0:9f7ee7ed13e4 | 57 | this->thetaWorld=-PI+(theta-PI/2); |
Ludwigfr | 0:9f7ee7ed13e4 | 58 | else |
Ludwigfr | 0:9f7ee7ed13e4 | 59 | this->thetaWorld=theta+PI/2; |
Ludwigfr | 0:9f7ee7ed13e4 | 60 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 61 | |
geotsam | 1:20f48907c726 | 62 | void MiniExplorerCoimbra::go_to_point(float targetXWorld, float targetYWorld) { |
geotsam | 1:20f48907c726 | 63 | |
geotsam | 1:20f48907c726 | 64 | float angleError; //angle error |
geotsam | 1:20f48907c726 | 65 | float d; //distance from target |
geotsam | 1:20f48907c726 | 66 | float angularLeft, angularRight, linear, angular; |
geotsam | 1:20f48907c726 | 67 | int speed=300; |
geotsam | 1:20f48907c726 | 68 | |
geotsam | 1:20f48907c726 | 69 | do { |
geotsam | 1:20f48907c726 | 70 | //Updating X,Y and theta with the odometry values |
geotsam | 1:20f48907c726 | 71 | this->myOdometria(); |
geotsam | 1:20f48907c726 | 72 | |
geotsam | 1:20f48907c726 | 73 | //Computing angle error and distance towards the target value |
geotsam | 1:20f48907c726 | 74 | angleError = atan2((targetYWorld-this->yWorld),(targetXWorld-this->xWorld))-this->thetaWorld; |
geotsam | 1:20f48907c726 | 75 | if(angleError>PI) angleError=-(angleError-PI); |
geotsam | 1:20f48907c726 | 76 | else if(angleError<-PI) angleError=-(angleError+PI); |
geotsam | 1:20f48907c726 | 77 | pc.printf("\n\r error=%f",angleError); |
geotsam | 1:20f48907c726 | 78 | |
geotsam | 1:20f48907c726 | 79 | d=this->dist(this->xWorld, this->yWorld, targetXWorld, targetYWorld); |
geotsam | 1:20f48907c726 | 80 | pc.printf("\n\r dist=%f/n", d); |
geotsam | 1:20f48907c726 | 81 | |
geotsam | 1:20f48907c726 | 82 | //Computing linear and angular velocities |
geotsam | 1:20f48907c726 | 83 | linear=k_linear*d; |
geotsam | 1:20f48907c726 | 84 | angular=k_angular*angleError; |
geotsam | 1:20f48907c726 | 85 | angularLeft=(linear-0.5*this->distanceWheels*angular)/this->radiusWheels; |
geotsam | 1:20f48907c726 | 86 | angularRight=(linear+0.5*this->distanceWheels*angular)/this->radiusWheels; |
geotsam | 1:20f48907c726 | 87 | |
geotsam | 1:20f48907c726 | 88 | |
geotsam | 1:20f48907c726 | 89 | //Normalize speed for motors |
geotsam | 1:20f48907c726 | 90 | if(angularLeft>angularRight) { |
geotsam | 1:20f48907c726 | 91 | angularRight=speed*angularRight/angularLeft; |
geotsam | 1:20f48907c726 | 92 | angularLeft=speed; |
geotsam | 1:20f48907c726 | 93 | } else { |
geotsam | 1:20f48907c726 | 94 | angularLeft=speed*angularLeft/angularRight; |
geotsam | 1:20f48907c726 | 95 | angularRight=speed; |
geotsam | 1:20f48907c726 | 96 | } |
geotsam | 1:20f48907c726 | 97 | |
geotsam | 1:20f48907c726 | 98 | pc.printf("\n\r X=%f", this->xWorld); |
geotsam | 1:20f48907c726 | 99 | pc.printf("\n\r Y=%f", this->yWorld); |
geotsam | 1:20f48907c726 | 100 | pc.printf("\n\r theta=%f", this->thetaWorld); |
geotsam | 1:20f48907c726 | 101 | |
geotsam | 1:20f48907c726 | 102 | //Updating motor velocities |
geotsam | 1:20f48907c726 | 103 | if(angularLeft>0){ |
geotsam | 1:20f48907c726 | 104 | leftMotor(1,angularLeft); |
geotsam | 1:20f48907c726 | 105 | } |
geotsam | 1:20f48907c726 | 106 | else{ |
geotsam | 1:20f48907c726 | 107 | leftMotor(0,-angularLeft); |
geotsam | 1:20f48907c726 | 108 | } |
geotsam | 1:20f48907c726 | 109 | |
geotsam | 1:20f48907c726 | 110 | if(angularRight>0){ |
geotsam | 1:20f48907c726 | 111 | rightMotor(1,angularRight); |
geotsam | 1:20f48907c726 | 112 | } |
geotsam | 1:20f48907c726 | 113 | else{ |
geotsam | 1:20f48907c726 | 114 | rightMotor(0,-angularRight); |
geotsam | 1:20f48907c726 | 115 | } |
geotsam | 1:20f48907c726 | 116 | |
Ludwigfr | 5:19f24c363418 | 117 | //wait(0.5); |
geotsam | 1:20f48907c726 | 118 | } while(d>1); |
geotsam | 1:20f48907c726 | 119 | |
geotsam | 1:20f48907c726 | 120 | //Stop at the end |
geotsam | 1:20f48907c726 | 121 | leftMotor(1,0); |
geotsam | 1:20f48907c726 | 122 | rightMotor(1,0); |
geotsam | 1:20f48907c726 | 123 | } |
geotsam | 1:20f48907c726 | 124 | |
Ludwigfr | 2:11cd5173aa36 | 125 | void MiniExplorerCoimbra::test_procedure_lab2(int nbIteration){ |
Ludwigfr | 2:11cd5173aa36 | 126 | for(int i=0;i<nbIteration;i++){ |
Ludwigfr | 2:11cd5173aa36 | 127 | this->randomize_and_map(); |
Ludwigfr | 5:19f24c363418 | 128 | //this->print_map_with_robot_position(); |
Ludwigfr | 2:11cd5173aa36 | 129 | } |
Ludwigfr | 3:37345c109dfc | 130 | while(1) |
Ludwigfr | 3:37345c109dfc | 131 | this->print_map_with_robot_position(); |
Ludwigfr | 2:11cd5173aa36 | 132 | } |
Ludwigfr | 2:11cd5173aa36 | 133 | |
Ludwigfr | 0:9f7ee7ed13e4 | 134 | //generate a position randomly and makes the robot go there while updating the map |
Ludwigfr | 0:9f7ee7ed13e4 | 135 | void MiniExplorerCoimbra::randomize_and_map() { |
Ludwigfr | 0:9f7ee7ed13e4 | 136 | //TODO check that it's aurelien's work |
Ludwigfr | 2:11cd5173aa36 | 137 | float movementOnX=rand()%(int)(this->map.widthRealMap); |
Ludwigfr | 2:11cd5173aa36 | 138 | float movementOnY=rand()%(int)(this->map.heightRealMap); |
Ludwigfr | 3:37345c109dfc | 139 | |
Ludwigfr | 3:37345c109dfc | 140 | float targetXWorld = movementOnX; |
Ludwigfr | 3:37345c109dfc | 141 | float targetYWorld = movementOnY; |
Ludwigfr | 3:37345c109dfc | 142 | float targetAngleWorld = 2*((float)(rand()%31416)-15708)/10000.0; |
Ludwigfr | 0:9f7ee7ed13e4 | 143 | |
Ludwigfr | 3:37345c109dfc | 144 | //target between (0,0) and (widthRealMap,heightRealMap) |
Ludwigfr | 0:9f7ee7ed13e4 | 145 | this->go_to_point_with_angle(targetXWorld, targetYWorld, targetAngleWorld); |
Ludwigfr | 0:9f7ee7ed13e4 | 146 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 147 | |
Ludwigfr | 2:11cd5173aa36 | 148 | void MiniExplorerCoimbra::test_sonars_and_map(int nbIteration){ |
Ludwigfr | 2:11cd5173aa36 | 149 | float leftMm; |
Ludwigfr | 2:11cd5173aa36 | 150 | float frontMm; |
Ludwigfr | 2:11cd5173aa36 | 151 | float rightMm; |
Ludwigfr | 2:11cd5173aa36 | 152 | this->myOdometria(); |
Ludwigfr | 2:11cd5173aa36 | 153 | this->print_map_with_robot_position(); |
Ludwigfr | 2:11cd5173aa36 | 154 | for(int i=0;i<nbIteration;i++){ |
Ludwigfr | 2:11cd5173aa36 | 155 | leftMm = get_distance_left_sensor(); |
Ludwigfr | 2:11cd5173aa36 | 156 | frontMm = get_distance_front_sensor(); |
Ludwigfr | 2:11cd5173aa36 | 157 | rightMm = get_distance_right_sensor(); |
Ludwigfr | 3:37345c109dfc | 158 | pc.printf("\n\r 1 leftMm= %f",leftMm); |
Ludwigfr | 3:37345c109dfc | 159 | pc.printf("\n\r 1 frontMm= %f",frontMm); |
Ludwigfr | 3:37345c109dfc | 160 | pc.printf("\n\r 1 rightMm= %f",rightMm); |
Ludwigfr | 2:11cd5173aa36 | 161 | this->update_sonar_values(leftMm, frontMm, rightMm); |
Ludwigfr | 2:11cd5173aa36 | 162 | this->print_map_with_robot_position(); |
Ludwigfr | 3:37345c109dfc | 163 | wait(1); |
Ludwigfr | 2:11cd5173aa36 | 164 | } |
Ludwigfr | 2:11cd5173aa36 | 165 | } |
Ludwigfr | 2:11cd5173aa36 | 166 | |
Ludwigfr | 2:11cd5173aa36 | 167 | |
Ludwigfr | 2:11cd5173aa36 | 168 | //generate a position randomly and makes the robot go there while updating the map |
Ludwigfr | 0:9f7ee7ed13e4 | 169 | //move of targetXWorld and targetYWorld ending in a targetAngleWorld |
Ludwigfr | 0:9f7ee7ed13e4 | 170 | void MiniExplorerCoimbra::go_to_point_with_angle(float targetXWorld, float targetYWorld, float targetAngleWorld) { |
Ludwigfr | 0:9f7ee7ed13e4 | 171 | bool keepGoing=true; |
Ludwigfr | 0:9f7ee7ed13e4 | 172 | float leftMm; |
Ludwigfr | 0:9f7ee7ed13e4 | 173 | float frontMm; |
Ludwigfr | 0:9f7ee7ed13e4 | 174 | float rightMm; |
Ludwigfr | 0:9f7ee7ed13e4 | 175 | float dt; |
Ludwigfr | 0:9f7ee7ed13e4 | 176 | Timer t; |
Ludwigfr | 0:9f7ee7ed13e4 | 177 | float distanceToTarget; |
Ludwigfr | 0:9f7ee7ed13e4 | 178 | do { |
Ludwigfr | 0:9f7ee7ed13e4 | 179 | //Timer stuff |
Ludwigfr | 0:9f7ee7ed13e4 | 180 | dt = t.read(); |
Ludwigfr | 0:9f7ee7ed13e4 | 181 | t.reset(); |
Ludwigfr | 0:9f7ee7ed13e4 | 182 | t.start(); |
Ludwigfr | 0:9f7ee7ed13e4 | 183 | |
Ludwigfr | 0:9f7ee7ed13e4 | 184 | //Updating X,Y and theta with the odometry values |
Ludwigfr | 0:9f7ee7ed13e4 | 185 | this->myOdometria(); |
Ludwigfr | 2:11cd5173aa36 | 186 | leftMm = get_distance_left_sensor(); |
Ludwigfr | 2:11cd5173aa36 | 187 | frontMm = get_distance_front_sensor(); |
Ludwigfr | 2:11cd5173aa36 | 188 | rightMm = get_distance_right_sensor(); |
Ludwigfr | 2:11cd5173aa36 | 189 | //if in dangerzone 150 mm |
Ludwigfr | 0:9f7ee7ed13e4 | 190 | if((frontMm < 150 && frontMm > 0)|| (leftMm <150 && leftMm > 0) || (rightMm <150 && rightMm > 0) ){ |
Ludwigfr | 2:11cd5173aa36 | 191 | //stop motors |
Ludwigfr | 0:9f7ee7ed13e4 | 192 | leftMotor(1,0); |
Ludwigfr | 0:9f7ee7ed13e4 | 193 | rightMotor(1,0); |
Ludwigfr | 2:11cd5173aa36 | 194 | //update the map |
Ludwigfr | 0:9f7ee7ed13e4 | 195 | this->update_sonar_values(leftMm, frontMm, rightMm); |
Ludwigfr | 0:9f7ee7ed13e4 | 196 | this->myOdometria(); |
Ludwigfr | 0:9f7ee7ed13e4 | 197 | keepGoing=false; |
Ludwigfr | 2:11cd5173aa36 | 198 | this->do_half_flip(); |
Ludwigfr | 0:9f7ee7ed13e4 | 199 | }else{ |
Ludwigfr | 0:9f7ee7ed13e4 | 200 | //if not in danger zone continue as usual |
Ludwigfr | 0:9f7ee7ed13e4 | 201 | this->update_sonar_values(leftMm, frontMm, rightMm); |
Ludwigfr | 2:11cd5173aa36 | 202 | //Updating motor velocities |
Ludwigfr | 0:9f7ee7ed13e4 | 203 | distanceToTarget=this->update_angular_speed_wheels_go_to_point_with_angle(targetXWorld,targetYWorld,targetAngleWorld,dt); |
Ludwigfr | 5:19f24c363418 | 204 | //wait(0.2); |
Ludwigfr | 0:9f7ee7ed13e4 | 205 | //Timer stuff |
Ludwigfr | 0:9f7ee7ed13e4 | 206 | t.stop(); |
Ludwigfr | 2:11cd5173aa36 | 207 | pc.printf("\n\rdist to target= %f",distanceToTarget); |
Ludwigfr | 0:9f7ee7ed13e4 | 208 | } |
Ludwigfr | 3:37345c109dfc | 209 | } while((distanceToTarget>2 || (abs(targetAngleWorld-this->thetaWorld)>PI/3)) && keepGoing); |
Ludwigfr | 0:9f7ee7ed13e4 | 210 | |
Ludwigfr | 0:9f7ee7ed13e4 | 211 | //Stop at the end |
Ludwigfr | 0:9f7ee7ed13e4 | 212 | leftMotor(1,0); |
Ludwigfr | 0:9f7ee7ed13e4 | 213 | rightMotor(1,0); |
Ludwigfr | 2:11cd5173aa36 | 214 | pc.printf("\r\nReached Target!"); |
Ludwigfr | 0:9f7ee7ed13e4 | 215 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 216 | |
geotsam | 1:20f48907c726 | 217 | //move of targetXWorld and targetYWorld ending in a targetAngleWorld |
geotsam | 1:20f48907c726 | 218 | void MiniExplorerCoimbra::go_to_point_with_angle_first_lab(float targetXWorld, float targetYWorld, float targetAngleWorld) { |
geotsam | 1:20f48907c726 | 219 | float dt; |
geotsam | 1:20f48907c726 | 220 | Timer t; |
geotsam | 1:20f48907c726 | 221 | float distanceToTarget; |
geotsam | 1:20f48907c726 | 222 | do { |
geotsam | 1:20f48907c726 | 223 | //Timer stuff |
geotsam | 1:20f48907c726 | 224 | dt = t.read(); |
geotsam | 1:20f48907c726 | 225 | t.reset(); |
geotsam | 1:20f48907c726 | 226 | t.start(); |
geotsam | 1:20f48907c726 | 227 | |
geotsam | 1:20f48907c726 | 228 | //Updating X,Y and theta with the odometry values |
geotsam | 1:20f48907c726 | 229 | this->myOdometria(); |
geotsam | 1:20f48907c726 | 230 | |
geotsam | 1:20f48907c726 | 231 | //Updating motor velocities |
geotsam | 1:20f48907c726 | 232 | distanceToTarget=this->update_angular_speed_wheels_go_to_point_with_angle(targetXWorld,targetYWorld,targetAngleWorld,dt); |
geotsam | 1:20f48907c726 | 233 | |
Ludwigfr | 5:19f24c363418 | 234 | //wait(0.2); |
geotsam | 1:20f48907c726 | 235 | //Timer stuff |
geotsam | 1:20f48907c726 | 236 | t.stop(); |
geotsam | 1:20f48907c726 | 237 | pc.printf("\n\rdist to target= %f",distanceToTarget); |
geotsam | 1:20f48907c726 | 238 | |
geotsam | 1:20f48907c726 | 239 | } while(distanceToTarget>1 || (abs(targetAngleWorld-this->thetaWorld)>0.1)); |
geotsam | 1:20f48907c726 | 240 | |
geotsam | 1:20f48907c726 | 241 | //Stop at the end |
geotsam | 1:20f48907c726 | 242 | leftMotor(1,0); |
geotsam | 1:20f48907c726 | 243 | rightMotor(1,0); |
geotsam | 1:20f48907c726 | 244 | pc.printf("\r\nReached Target!"); |
geotsam | 1:20f48907c726 | 245 | } |
geotsam | 1:20f48907c726 | 246 | |
Ludwigfr | 0:9f7ee7ed13e4 | 247 | float MiniExplorerCoimbra::update_angular_speed_wheels_go_to_point_with_angle(float targetXWorld, float targetYWorld, float targetAngleWorld, float dt){ |
Ludwigfr | 0:9f7ee7ed13e4 | 248 | //compute_angles_and_distance |
Ludwigfr | 0:9f7ee7ed13e4 | 249 | //atan2 take the deplacement on x and the deplacement on y as parameters |
Ludwigfr | 0:9f7ee7ed13e4 | 250 | float angleToPoint = atan2((targetYWorld-this->yWorld),(targetXWorld-this->xWorld))-this->thetaWorld; |
geotsam | 1:20f48907c726 | 251 | |
geotsam | 1:20f48907c726 | 252 | if(angleToPoint>PI) angleToPoint=-(angleToPoint-PI); |
Ludwigfr | 3:37345c109dfc | 253 | else if(angleToPoint<-PI) angleToPoint=-(angleToPoint+PI); |
geotsam | 1:20f48907c726 | 254 | |
Ludwigfr | 3:37345c109dfc | 255 | //rho is the distance to the point of arrival |
Ludwigfr | 0:9f7ee7ed13e4 | 256 | float rho = dist(targetXWorld,targetYWorld,this->xWorld,this->yWorld); |
Ludwigfr | 0:9f7ee7ed13e4 | 257 | float distanceToTarget = rho; |
Ludwigfr | 0:9f7ee7ed13e4 | 258 | //TODO check that |
Ludwigfr | 0:9f7ee7ed13e4 | 259 | float beta = targetAngleWorld-angleToPoint-this->thetaWorld; |
Ludwigfr | 0:9f7ee7ed13e4 | 260 | |
Ludwigfr | 0:9f7ee7ed13e4 | 261 | //Computing angle error and distance towards the target value |
Ludwigfr | 0:9f7ee7ed13e4 | 262 | rho += dt*(-this->khro*cos(angleToPoint)*rho); |
Ludwigfr | 0:9f7ee7ed13e4 | 263 | float temp = angleToPoint; |
Ludwigfr | 0:9f7ee7ed13e4 | 264 | angleToPoint += dt*(this->khro*sin(angleToPoint)-this->ka*angleToPoint-this->kb*beta); |
Ludwigfr | 0:9f7ee7ed13e4 | 265 | beta += dt*(-this->khro*sin(temp)); |
Ludwigfr | 0:9f7ee7ed13e4 | 266 | |
Ludwigfr | 0:9f7ee7ed13e4 | 267 | //Computing linear and angular velocities |
Ludwigfr | 0:9f7ee7ed13e4 | 268 | float linear; |
Ludwigfr | 0:9f7ee7ed13e4 | 269 | float angular; |
Ludwigfr | 0:9f7ee7ed13e4 | 270 | if(angleToPoint>=-1.5708 && angleToPoint<=1.5708){ |
Ludwigfr | 0:9f7ee7ed13e4 | 271 | linear=this->khro*rho; |
Ludwigfr | 0:9f7ee7ed13e4 | 272 | angular=this->ka*angleToPoint+this->kb*beta; |
Ludwigfr | 0:9f7ee7ed13e4 | 273 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 274 | else{ |
Ludwigfr | 0:9f7ee7ed13e4 | 275 | linear=-this->khro*rho; |
Ludwigfr | 0:9f7ee7ed13e4 | 276 | angular=-this->ka*angleToPoint-this->kb*beta; |
Ludwigfr | 0:9f7ee7ed13e4 | 277 | } |
geotsam | 1:20f48907c726 | 278 | |
geotsam | 1:20f48907c726 | 279 | float angularLeft=(linear-0.5*this->distanceWheels*angular)/this->radiusWheels; |
geotsam | 1:20f48907c726 | 280 | float angularRight=(linear+0.5*this->distanceWheels*angular)/this->radiusWheels; |
geotsam | 1:20f48907c726 | 281 | |
geotsam | 1:20f48907c726 | 282 | //Slowing down at the end for more precision |
geotsam | 1:20f48907c726 | 283 | if (distanceToTarget<30) { |
geotsam | 1:20f48907c726 | 284 | this->speed = distanceToTarget*10; |
geotsam | 1:20f48907c726 | 285 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 286 | |
Ludwigfr | 0:9f7ee7ed13e4 | 287 | //Normalize speed for motors |
geotsam | 1:20f48907c726 | 288 | if(angularLeft>angularRight) { |
geotsam | 1:20f48907c726 | 289 | angularRight=this->speed*angularRight/angularLeft; |
geotsam | 1:20f48907c726 | 290 | angularLeft=this->speed; |
Ludwigfr | 0:9f7ee7ed13e4 | 291 | } else { |
geotsam | 1:20f48907c726 | 292 | angularLeft=this->speed*angularLeft/angularRight; |
geotsam | 1:20f48907c726 | 293 | angularRight=this->speed; |
Ludwigfr | 0:9f7ee7ed13e4 | 294 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 295 | |
Ludwigfr | 0:9f7ee7ed13e4 | 296 | //compute_linear_angular_velocities |
geotsam | 1:20f48907c726 | 297 | leftMotor(1,angularLeft); |
geotsam | 1:20f48907c726 | 298 | rightMotor(1,angularRight); |
Ludwigfr | 0:9f7ee7ed13e4 | 299 | |
Ludwigfr | 0:9f7ee7ed13e4 | 300 | return distanceToTarget; |
Ludwigfr | 0:9f7ee7ed13e4 | 301 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 302 | |
Ludwigfr | 0:9f7ee7ed13e4 | 303 | void MiniExplorerCoimbra::update_sonar_values(float leftMm,float frontMm,float rightMm){ |
Ludwigfr | 0:9f7ee7ed13e4 | 304 | float xWorldCell; |
Ludwigfr | 0:9f7ee7ed13e4 | 305 | float yWorldCell; |
Ludwigfr | 3:37345c109dfc | 306 | float probaLeft; |
Ludwigfr | 3:37345c109dfc | 307 | float probaFront; |
Ludwigfr | 3:37345c109dfc | 308 | float probaRight; |
Ludwigfr | 3:37345c109dfc | 309 | float leftCm=leftMm/10; |
Ludwigfr | 3:37345c109dfc | 310 | float frontCm=frontMm/10; |
Ludwigfr | 3:37345c109dfc | 311 | float rightCm=rightMm/10; |
Ludwigfr | 0:9f7ee7ed13e4 | 312 | for(int i=0;i<this->map.nbCellWidth;i++){ |
Ludwigfr | 0:9f7ee7ed13e4 | 313 | for(int j=0;j<this->map.nbCellHeight;j++){ |
Ludwigfr | 0:9f7ee7ed13e4 | 314 | xWorldCell=this->map.cell_width_coordinate_to_world(i); |
Ludwigfr | 0:9f7ee7ed13e4 | 315 | yWorldCell=this->map.cell_height_coordinate_to_world(j); |
Ludwigfr | 3:37345c109dfc | 316 | |
Ludwigfr | 3:37345c109dfc | 317 | probaLeft=this->sonarLeft.compute_probability_t(leftCm,xWorldCell,yWorldCell,this->xWorld,this->yWorld,this->thetaWorld); |
Ludwigfr | 3:37345c109dfc | 318 | probaFront=this->sonarFront.compute_probability_t(frontCm,xWorldCell,yWorldCell,this->xWorld,this->yWorld,this->thetaWorld); |
Ludwigfr | 3:37345c109dfc | 319 | probaRight=this->sonarRight.compute_probability_t(rightCm,xWorldCell,yWorldCell,this->xWorld,this->yWorld,this->thetaWorld); |
Ludwigfr | 3:37345c109dfc | 320 | |
Ludwigfr | 3:37345c109dfc | 321 | /* |
Ludwigfr | 3:37345c109dfc | 322 | pc.printf("\n\r leftCm= %f",leftCm); |
Ludwigfr | 3:37345c109dfc | 323 | pc.printf("\n\r frontCm= %f",frontCm); |
Ludwigfr | 3:37345c109dfc | 324 | pc.printf("\n\r rightCm= %f",rightCm); |
Ludwigfr | 3:37345c109dfc | 325 | */ |
Ludwigfr | 3:37345c109dfc | 326 | /* |
Ludwigfr | 3:37345c109dfc | 327 | pc.printf("\n\r probaLeft= %f",probaLeft); |
Ludwigfr | 3:37345c109dfc | 328 | pc.printf("\n\r probaFront= %f",probaFront); |
Ludwigfr | 3:37345c109dfc | 329 | pc.printf("\n\r probaRight= %f",probaRight); |
Ludwigfr | 3:37345c109dfc | 330 | if(probaLeft> 1 || probaLeft < 0 || probaFront> 1 || probaFront < 0 ||probaRight> 1 || probaRight < 0)){ |
Ludwigfr | 3:37345c109dfc | 331 | pwm_buzzer.pulsewidth_us(250); |
Ludwigfr | 3:37345c109dfc | 332 | wait_ms(50); |
Ludwigfr | 3:37345c109dfc | 333 | pwm_buzzer.pulsewidth_us(0); |
Ludwigfr | 3:37345c109dfc | 334 | wait(20); |
Ludwigfr | 3:37345c109dfc | 335 | pwm_buzzer.pulsewidth_us(250); |
Ludwigfr | 3:37345c109dfc | 336 | wait_ms(50); |
Ludwigfr | 3:37345c109dfc | 337 | pwm_buzzer.pulsewidth_us(0); |
Ludwigfr | 3:37345c109dfc | 338 | } |
Ludwigfr | 3:37345c109dfc | 339 | */ |
Ludwigfr | 3:37345c109dfc | 340 | this->map.update_cell_value(i,j,probaLeft); |
Ludwigfr | 3:37345c109dfc | 341 | this->map.update_cell_value(i,j,probaFront); |
Ludwigfr | 3:37345c109dfc | 342 | this->map.update_cell_value(i,j,probaRight); |
Ludwigfr | 0:9f7ee7ed13e4 | 343 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 344 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 345 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 346 | |
Ludwigfr | 0:9f7ee7ed13e4 | 347 | void MiniExplorerCoimbra::do_half_flip(){ |
Ludwigfr | 0:9f7ee7ed13e4 | 348 | this->myOdometria(); |
Ludwigfr | 0:9f7ee7ed13e4 | 349 | float theta_plus_h_pi=theta+PI/2;//theta is between -PI and PI |
Ludwigfr | 0:9f7ee7ed13e4 | 350 | if(theta_plus_h_pi > PI) |
Ludwigfr | 0:9f7ee7ed13e4 | 351 | theta_plus_h_pi=-(2*PI-theta_plus_h_pi); |
Ludwigfr | 0:9f7ee7ed13e4 | 352 | leftMotor(0,100); |
Ludwigfr | 0:9f7ee7ed13e4 | 353 | rightMotor(1,100); |
Ludwigfr | 0:9f7ee7ed13e4 | 354 | while(abs(theta_plus_h_pi-theta)>0.05){ |
Ludwigfr | 0:9f7ee7ed13e4 | 355 | this->myOdometria(); |
Ludwigfr | 0:9f7ee7ed13e4 | 356 | // pc.printf("\n\r diff=%f", abs(theta_plus_pi-theta)); |
Ludwigfr | 0:9f7ee7ed13e4 | 357 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 358 | leftMotor(1,0); |
Ludwigfr | 0:9f7ee7ed13e4 | 359 | rightMotor(1,0); |
Ludwigfr | 0:9f7ee7ed13e4 | 360 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 361 | |
Ludwigfr | 0:9f7ee7ed13e4 | 362 | //Distance computation function |
Ludwigfr | 0:9f7ee7ed13e4 | 363 | float MiniExplorerCoimbra::dist(float x1, float y1, float x2, float y2){ |
Ludwigfr | 0:9f7ee7ed13e4 | 364 | return sqrt(pow(y2-y1,2) + pow(x2-x1,2)); |
Ludwigfr | 0:9f7ee7ed13e4 | 365 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 366 | |
Ludwigfr | 0:9f7ee7ed13e4 | 367 | //use virtual force field |
Ludwigfr | 0:9f7ee7ed13e4 | 368 | void MiniExplorerCoimbra::try_to_reach_target(float targetXWorld,float targetYWorld){ |
Ludwigfr | 0:9f7ee7ed13e4 | 369 | //atan2 gives the angle beetween PI and -PI |
Ludwigfr | 0:9f7ee7ed13e4 | 370 | this->myOdometria(); |
Ludwigfr | 0:9f7ee7ed13e4 | 371 | /* |
Ludwigfr | 0:9f7ee7ed13e4 | 372 | float deplacementOnXWorld=targetXWorld-this->xWorld; |
Ludwigfr | 0:9f7ee7ed13e4 | 373 | float deplacementOnYWorld=targetYWorld-this->yWorld; |
Ludwigfr | 0:9f7ee7ed13e4 | 374 | */ |
Ludwigfr | 3:37345c109dfc | 375 | //float angleToTarget=atan2(targetYWorld-this->yWorld,targetXWorld-this->xWorld); |
Ludwigfr | 3:37345c109dfc | 376 | //pc.printf("\n angleToTarget=%f",angleToTarget); |
Ludwigfr | 3:37345c109dfc | 377 | //turn_to_target(angleToTarget); |
Ludwigfr | 3:37345c109dfc | 378 | //TODO IDEA check if maybe set a low max range |
Ludwigfr | 3:37345c109dfc | 379 | //this->sonarLeft.setMaxRange(30); |
Ludwigfr | 3:37345c109dfc | 380 | //this->sonarFront.setMaxRange(30); |
Ludwigfr | 3:37345c109dfc | 381 | //this->sonarRight.setMaxRange(30); |
Ludwigfr | 0:9f7ee7ed13e4 | 382 | bool reached=false; |
Ludwigfr | 0:9f7ee7ed13e4 | 383 | int print=0; |
Ludwigfr | 3:37345c109dfc | 384 | int printLimit=1000; |
Ludwigfr | 0:9f7ee7ed13e4 | 385 | while (!reached) { |
Ludwigfr | 0:9f7ee7ed13e4 | 386 | this->vff(&reached,targetXWorld,targetYWorld); |
Ludwigfr | 0:9f7ee7ed13e4 | 387 | //test_got_to_line(&reached); |
Ludwigfr | 3:37345c109dfc | 388 | if(print==printLimit){ |
Ludwigfr | 0:9f7ee7ed13e4 | 389 | leftMotor(1,0); |
Ludwigfr | 0:9f7ee7ed13e4 | 390 | rightMotor(1,0); |
Ludwigfr | 0:9f7ee7ed13e4 | 391 | this->print_map_with_robot_position_and_target(targetXWorld,targetYWorld); |
Ludwigfr | 0:9f7ee7ed13e4 | 392 | print=0; |
Ludwigfr | 0:9f7ee7ed13e4 | 393 | }else |
Ludwigfr | 0:9f7ee7ed13e4 | 394 | print+=1; |
Ludwigfr | 0:9f7ee7ed13e4 | 395 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 396 | //Stop at the end |
Ludwigfr | 0:9f7ee7ed13e4 | 397 | leftMotor(1,0); |
Ludwigfr | 0:9f7ee7ed13e4 | 398 | rightMotor(1,0); |
Ludwigfr | 0:9f7ee7ed13e4 | 399 | pc.printf("\r\n target reached"); |
Ludwigfr | 5:19f24c363418 | 400 | //wait(3);// |
Ludwigfr | 0:9f7ee7ed13e4 | 401 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 402 | |
Ludwigfr | 0:9f7ee7ed13e4 | 403 | void MiniExplorerCoimbra::vff(bool* reached, float targetXWorld, float targetYWorld){ |
Ludwigfr | 0:9f7ee7ed13e4 | 404 | float line_a; |
Ludwigfr | 0:9f7ee7ed13e4 | 405 | float line_b; |
Ludwigfr | 0:9f7ee7ed13e4 | 406 | float line_c; |
Ludwigfr | 0:9f7ee7ed13e4 | 407 | //Updating X,Y and theta with the odometry values |
Ludwigfr | 0:9f7ee7ed13e4 | 408 | float forceXWorld=0; |
Ludwigfr | 0:9f7ee7ed13e4 | 409 | float forceYWorld=0; |
Ludwigfr | 0:9f7ee7ed13e4 | 410 | //we update the odometrie |
Ludwigfr | 0:9f7ee7ed13e4 | 411 | this->myOdometria(); |
Ludwigfr | 0:9f7ee7ed13e4 | 412 | //we check the sensors |
Ludwigfr | 0:9f7ee7ed13e4 | 413 | float leftMm = get_distance_left_sensor(); |
Ludwigfr | 0:9f7ee7ed13e4 | 414 | float frontMm = get_distance_front_sensor(); |
Ludwigfr | 0:9f7ee7ed13e4 | 415 | float rightMm = get_distance_right_sensor(); |
Ludwigfr | 0:9f7ee7ed13e4 | 416 | //update the probabilities values |
Ludwigfr | 0:9f7ee7ed13e4 | 417 | this->update_sonar_values(leftMm, frontMm, rightMm); |
Ludwigfr | 8:072a76960e27 | 418 | this->myOdometria(); |
Ludwigfr | 0:9f7ee7ed13e4 | 419 | //we compute the force on X and Y |
Ludwigfr | 0:9f7ee7ed13e4 | 420 | this->compute_forceX_and_forceY(&forceXWorld, &forceYWorld,targetXWorld,targetYWorld); |
Ludwigfr | 0:9f7ee7ed13e4 | 421 | //we compute a new ine |
Ludwigfr | 0:9f7ee7ed13e4 | 422 | this->calculate_line(forceXWorld, forceYWorld, &line_a,&line_b,&line_c); |
Ludwigfr | 0:9f7ee7ed13e4 | 423 | //Updating motor velocities |
Ludwigfr | 8:072a76960e27 | 424 | //pc.printf("\r\nX=%f;Y=%f",xWorld,yWorld); |
Ludwigfr | 8:072a76960e27 | 425 | //pc.printf("\r\n%f*x+%f*y+%f=0",line_a,line_b,line_c); |
Ludwigfr | 0:9f7ee7ed13e4 | 426 | this->go_to_line(line_a,line_b,line_c,targetXWorld,targetYWorld); |
Ludwigfr | 3:37345c109dfc | 427 | |
Ludwigfr | 0:9f7ee7ed13e4 | 428 | //wait(0.1); |
Ludwigfr | 0:9f7ee7ed13e4 | 429 | this->myOdometria(); |
Ludwigfr | 3:37345c109dfc | 430 | if(dist(this->xWorld,this->yWorld,targetXWorld,targetYWorld)<3) |
Ludwigfr | 0:9f7ee7ed13e4 | 431 | *reached=true; |
Ludwigfr | 0:9f7ee7ed13e4 | 432 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 433 | |
Ludwigfr | 0:9f7ee7ed13e4 | 434 | /*angleToTarget is obtained through atan2 so it s: |
Ludwigfr | 0:9f7ee7ed13e4 | 435 | < 0 if the angle is bettween PI and 2pi on a trigo circle |
Ludwigfr | 0:9f7ee7ed13e4 | 436 | > 0 if it is between 0 and PI |
Ludwigfr | 0:9f7ee7ed13e4 | 437 | */ |
Ludwigfr | 0:9f7ee7ed13e4 | 438 | void MiniExplorerCoimbra::turn_to_target(float angleToTarget){ |
Ludwigfr | 0:9f7ee7ed13e4 | 439 | this->myOdometria(); |
Ludwigfr | 3:37345c109dfc | 440 | if(angleToTarget!=0){ |
Ludwigfr | 3:37345c109dfc | 441 | if(angleToTarget>0){ |
Ludwigfr | 3:37345c109dfc | 442 | leftMotor(0,1); |
Ludwigfr | 3:37345c109dfc | 443 | rightMotor(1,1); |
Ludwigfr | 3:37345c109dfc | 444 | }else{ |
Ludwigfr | 3:37345c109dfc | 445 | leftMotor(1,1); |
Ludwigfr | 3:37345c109dfc | 446 | rightMotor(0,1); |
Ludwigfr | 3:37345c109dfc | 447 | } |
Ludwigfr | 3:37345c109dfc | 448 | while(abs(angleToTarget-this->thetaWorld)>0.05) |
Ludwigfr | 3:37345c109dfc | 449 | this->myOdometria(); |
Ludwigfr | 0:9f7ee7ed13e4 | 450 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 451 | leftMotor(1,0); |
Ludwigfr | 0:9f7ee7ed13e4 | 452 | rightMotor(1,0); |
Ludwigfr | 0:9f7ee7ed13e4 | 453 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 454 | |
Ludwigfr | 0:9f7ee7ed13e4 | 455 | |
Ludwigfr | 0:9f7ee7ed13e4 | 456 | void MiniExplorerCoimbra::print_map_with_robot_position_and_target(float targetXWorld, float targetYWorld) { |
Ludwigfr | 0:9f7ee7ed13e4 | 457 | float currProba; |
Ludwigfr | 0:9f7ee7ed13e4 | 458 | |
Ludwigfr | 0:9f7ee7ed13e4 | 459 | float heightIndiceInOrthonormal; |
Ludwigfr | 0:9f7ee7ed13e4 | 460 | float widthIndiceInOrthonormal; |
Ludwigfr | 0:9f7ee7ed13e4 | 461 | |
Ludwigfr | 0:9f7ee7ed13e4 | 462 | float widthMalus=-(3*this->map.sizeCellWidth/2); |
Ludwigfr | 0:9f7ee7ed13e4 | 463 | float widthBonus=this->map.sizeCellWidth/2; |
Ludwigfr | 0:9f7ee7ed13e4 | 464 | |
Ludwigfr | 0:9f7ee7ed13e4 | 465 | float heightMalus=-(3*this->map.sizeCellHeight/2); |
Ludwigfr | 0:9f7ee7ed13e4 | 466 | float heightBonus=this->map.sizeCellHeight/2; |
Ludwigfr | 0:9f7ee7ed13e4 | 467 | |
Ludwigfr | 0:9f7ee7ed13e4 | 468 | pc.printf("\n\r"); |
Ludwigfr | 0:9f7ee7ed13e4 | 469 | for (int y = this->map.nbCellHeight -1; y>-1; y--) { |
Ludwigfr | 0:9f7ee7ed13e4 | 470 | for (int x= 0; x<this->map.nbCellWidth; x++) { |
Ludwigfr | 0:9f7ee7ed13e4 | 471 | heightIndiceInOrthonormal=this->map.cell_height_coordinate_to_world(y); |
Ludwigfr | 0:9f7ee7ed13e4 | 472 | widthIndiceInOrthonormal=this->map.cell_width_coordinate_to_world(x); |
Ludwigfr | 0:9f7ee7ed13e4 | 473 | if(this->yWorld >= (heightIndiceInOrthonormal+heightMalus) && this->yWorld <= (heightIndiceInOrthonormal+heightBonus) && this->xWorld >= (widthIndiceInOrthonormal+widthMalus) && this->xWorld <= (widthIndiceInOrthonormal+widthBonus)) |
Ludwigfr | 0:9f7ee7ed13e4 | 474 | pc.printf(" R "); |
Ludwigfr | 0:9f7ee7ed13e4 | 475 | else{ |
Ludwigfr | 0:9f7ee7ed13e4 | 476 | if(targetYWorld >= (heightIndiceInOrthonormal+heightMalus) && targetYWorld <= (heightIndiceInOrthonormal+heightBonus) && targetXWorld >= (widthIndiceInOrthonormal+widthMalus) && targetXWorld <= (widthIndiceInOrthonormal+widthBonus)) |
Ludwigfr | 0:9f7ee7ed13e4 | 477 | pc.printf(" T "); |
Ludwigfr | 0:9f7ee7ed13e4 | 478 | else{ |
Ludwigfr | 0:9f7ee7ed13e4 | 479 | currProba=this->map.log_to_proba(this->map.cellsLogValues[x][y]); |
Ludwigfr | 5:19f24c363418 | 480 | if ( currProba < 0.5){ |
Ludwigfr | 0:9f7ee7ed13e4 | 481 | pc.printf(" "); |
Ludwigfr | 5:19f24c363418 | 482 | //pc.printf("%f",currProba); |
Ludwigfr | 5:19f24c363418 | 483 | }else{ |
Ludwigfr | 5:19f24c363418 | 484 | if(currProba==0.5){ |
Ludwigfr | 0:9f7ee7ed13e4 | 485 | pc.printf(" . "); |
Ludwigfr | 5:19f24c363418 | 486 | //pc.printf("%f",currProba); |
Ludwigfr | 5:19f24c363418 | 487 | }else{ |
Ludwigfr | 0:9f7ee7ed13e4 | 488 | pc.printf(" X "); |
Ludwigfr | 5:19f24c363418 | 489 | //pc.printf("%f",currProba); |
Ludwigfr | 5:19f24c363418 | 490 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 491 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 492 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 493 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 494 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 495 | pc.printf("\n\r"); |
Ludwigfr | 0:9f7ee7ed13e4 | 496 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 497 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 498 | |
Ludwigfr | 2:11cd5173aa36 | 499 | void MiniExplorerCoimbra::print_map_with_robot_position(){ |
Ludwigfr | 2:11cd5173aa36 | 500 | float currProba; |
Ludwigfr | 2:11cd5173aa36 | 501 | |
Ludwigfr | 2:11cd5173aa36 | 502 | float heightIndiceInOrthonormal; |
Ludwigfr | 2:11cd5173aa36 | 503 | float widthIndiceInOrthonormal; |
Ludwigfr | 2:11cd5173aa36 | 504 | |
Ludwigfr | 2:11cd5173aa36 | 505 | float widthMalus=-(3*this->map.sizeCellWidth/2); |
Ludwigfr | 2:11cd5173aa36 | 506 | float widthBonus=this->map.sizeCellWidth/2; |
Ludwigfr | 2:11cd5173aa36 | 507 | |
Ludwigfr | 2:11cd5173aa36 | 508 | float heightMalus=-(3*this->map.sizeCellHeight/2); |
Ludwigfr | 2:11cd5173aa36 | 509 | float heightBonus=this->map.sizeCellHeight/2; |
Ludwigfr | 2:11cd5173aa36 | 510 | |
Ludwigfr | 2:11cd5173aa36 | 511 | pc.printf("\n\r"); |
Ludwigfr | 2:11cd5173aa36 | 512 | for (int y = this->map.nbCellHeight -1; y>-1; y--) { |
Ludwigfr | 2:11cd5173aa36 | 513 | for (int x= 0; x<this->map.nbCellWidth; x++) { |
Ludwigfr | 2:11cd5173aa36 | 514 | heightIndiceInOrthonormal=this->map.cell_height_coordinate_to_world(y); |
Ludwigfr | 2:11cd5173aa36 | 515 | widthIndiceInOrthonormal=this->map.cell_width_coordinate_to_world(x); |
Ludwigfr | 5:19f24c363418 | 516 | if(this->yWorld >= (heightIndiceInOrthonormal+heightMalus) && this->yWorld <= (heightIndiceInOrthonormal+heightBonus) && this->xWorld >= (widthIndiceInOrthonormal+widthMalus) && this->xWorld <= (widthIndiceInOrthonormal+widthBonus)){ |
Ludwigfr | 2:11cd5173aa36 | 517 | pc.printf(" R "); |
Ludwigfr | 5:19f24c363418 | 518 | //pc.printf("%f",currProba); |
Ludwigfr | 5:19f24c363418 | 519 | }else{ |
Ludwigfr | 2:11cd5173aa36 | 520 | currProba=this->map.log_to_proba(this->map.cellsLogValues[x][y]); |
Ludwigfr | 5:19f24c363418 | 521 | if ( currProba < 0.5){ |
Ludwigfr | 2:11cd5173aa36 | 522 | pc.printf(" "); |
Ludwigfr | 5:19f24c363418 | 523 | //pc.printf("%f",currProba); |
Ludwigfr | 5:19f24c363418 | 524 | }else{ |
Ludwigfr | 5:19f24c363418 | 525 | if(currProba==0.5){ |
Ludwigfr | 2:11cd5173aa36 | 526 | pc.printf(" . "); |
Ludwigfr | 5:19f24c363418 | 527 | //pc.printf("%f",currProba); |
Ludwigfr | 5:19f24c363418 | 528 | }else{ |
Ludwigfr | 5:19f24c363418 | 529 | pc.printf(" X "); |
Ludwigfr | 5:19f24c363418 | 530 | //pc.printf("%f",currProba); |
Ludwigfr | 5:19f24c363418 | 531 | } |
Ludwigfr | 2:11cd5173aa36 | 532 | } |
Ludwigfr | 2:11cd5173aa36 | 533 | } |
Ludwigfr | 2:11cd5173aa36 | 534 | } |
Ludwigfr | 2:11cd5173aa36 | 535 | pc.printf("\n\r"); |
Ludwigfr | 2:11cd5173aa36 | 536 | } |
Ludwigfr | 2:11cd5173aa36 | 537 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 538 | |
Ludwigfr | 0:9f7ee7ed13e4 | 539 | //robotX and robotY are from this->myOdometria(), calculate line_a, line_b and line_c |
Ludwigfr | 0:9f7ee7ed13e4 | 540 | void MiniExplorerCoimbra::calculate_line(float forceX, float forceY, float *line_a, float *line_b, float *line_c){ |
Ludwigfr | 0:9f7ee7ed13e4 | 541 | /* |
Ludwigfr | 0:9f7ee7ed13e4 | 542 | in the teachers maths it is |
Ludwigfr | 0:9f7ee7ed13e4 | 543 | |
Ludwigfr | 0:9f7ee7ed13e4 | 544 | *line_a=forceY; |
Ludwigfr | 0:9f7ee7ed13e4 | 545 | *line_b=-forceX; |
Ludwigfr | 0:9f7ee7ed13e4 | 546 | |
Ludwigfr | 0:9f7ee7ed13e4 | 547 | because a*x+b*y+c=0 |
Ludwigfr | 0:9f7ee7ed13e4 | 548 | a impact the vertical and b the horizontal |
Ludwigfr | 0:9f7ee7ed13e4 | 549 | and he has to put them like this because |
Ludwigfr | 0:9f7ee7ed13e4 | 550 | Robot space: World space: |
Ludwigfr | 0:9f7ee7ed13e4 | 551 | ^ ^ |
Ludwigfr | 0:9f7ee7ed13e4 | 552 | |x |y |
Ludwigfr | 0:9f7ee7ed13e4 | 553 | <- R O -> |
Ludwigfr | 0:9f7ee7ed13e4 | 554 | y x |
Ludwigfr | 0:9f7ee7ed13e4 | 555 | but since our forceX, forceY are already computed in the orthonormal space I m not sure we need to |
Ludwigfr | 0:9f7ee7ed13e4 | 556 | */ |
Ludwigfr | 3:37345c109dfc | 557 | //*line_a=forceX; |
Ludwigfr | 3:37345c109dfc | 558 | //*line_b=forceY; |
Ludwigfr | 3:37345c109dfc | 559 | |
Ludwigfr | 3:37345c109dfc | 560 | *line_a=forceY; |
Ludwigfr | 3:37345c109dfc | 561 | *line_b=-forceX; |
Ludwigfr | 0:9f7ee7ed13e4 | 562 | //because the line computed always pass by the robot center we dont need lince_c |
Ludwigfr | 8:072a76960e27 | 563 | *line_c=forceX*this->yWorld+forceY*this->xWorld; |
Ludwigfr | 8:072a76960e27 | 564 | //*line_c=0; |
Ludwigfr | 0:9f7ee7ed13e4 | 565 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 566 | //compute the force on X and Y |
Ludwigfr | 0:9f7ee7ed13e4 | 567 | void MiniExplorerCoimbra::compute_forceX_and_forceY(float* forceXWorld, float* forceYWorld, float targetXWorld, float targetYWorld){ |
Ludwigfr | 0:9f7ee7ed13e4 | 568 | float forceRepulsionComputedX=0; |
Ludwigfr | 0:9f7ee7ed13e4 | 569 | float forceRepulsionComputedY=0; |
Ludwigfr | 8:072a76960e27 | 570 | this->print_map_with_robot_position(); |
Ludwigfr | 8:072a76960e27 | 571 | for(int i=0;i<this->map.nbCellWidth;i++){ //for each cell of the map we compute a force of repulsion |
Ludwigfr | 0:9f7ee7ed13e4 | 572 | for(int j=0;j<this->map.nbCellHeight;j++){ |
Ludwigfr | 0:9f7ee7ed13e4 | 573 | this->update_force(i,j,&forceRepulsionComputedX,&forceRepulsionComputedY); |
Ludwigfr | 0:9f7ee7ed13e4 | 574 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 575 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 576 | //update with attraction force |
Ludwigfr | 3:37345c109dfc | 577 | *forceXWorld=forceRepulsionComputedX; |
Ludwigfr | 3:37345c109dfc | 578 | *forceYWorld=forceRepulsionComputedY; |
Ludwigfr | 8:072a76960e27 | 579 | //this->print_map_with_robot_position(); |
Ludwigfr | 8:072a76960e27 | 580 | //pc.printf("\r\nForce X repul:%f",*forceXWorld); |
Ludwigfr | 8:072a76960e27 | 581 | //pc.printf("\r\nForce Y repul:%f",*forceYWorld); |
Ludwigfr | 9:1cc27f33d3e1 | 582 | |
Ludwigfr | 9:1cc27f33d3e1 | 583 | //test without atraction being impacted by distance |
Ludwigfr | 9:1cc27f33d3e1 | 584 | //*forceXWorld+=this->attractionConstantForce*(targetXWorld-this->xWorld); |
Ludwigfr | 9:1cc27f33d3e1 | 585 | //*forceYWorld+=this->attractionConstantForce*(targetYWorld-this->yWorld); |
Ludwigfr | 9:1cc27f33d3e1 | 586 | |
Ludwigfr | 0:9f7ee7ed13e4 | 587 | float distanceTargetRobot=sqrt(pow(targetXWorld-this->xWorld,2)+pow(targetYWorld-this->yWorld,2)); |
Ludwigfr | 0:9f7ee7ed13e4 | 588 | if(distanceTargetRobot != 0){ |
Ludwigfr | 8:072a76960e27 | 589 | *forceXWorld+=this->attractionConstantForce*(targetXWorld-this->xWorld)/distanceTargetRobot; |
Ludwigfr | 8:072a76960e27 | 590 | *forceYWorld+=this->attractionConstantForce*(targetYWorld-this->yWorld)/distanceTargetRobot; |
Ludwigfr | 3:37345c109dfc | 591 | }else{ |
Ludwigfr | 8:072a76960e27 | 592 | *forceXWorld+=this->attractionConstantForce*(targetXWorld-this->xWorld)/0.001; |
Ludwigfr | 8:072a76960e27 | 593 | *forceYWorld+=this->attractionConstantForce*(targetYWorld-this->yWorld)/0.001; |
Ludwigfr | 0:9f7ee7ed13e4 | 594 | } |
Ludwigfr | 9:1cc27f33d3e1 | 595 | |
Ludwigfr | 8:072a76960e27 | 596 | //pc.printf("\r\nForce X after attract:%f",*forceXWorld); |
Ludwigfr | 8:072a76960e27 | 597 | //pc.printf("\r\nForce Y after attract:%f",*forceYWorld); |
Ludwigfr | 3:37345c109dfc | 598 | |
Ludwigfr | 0:9f7ee7ed13e4 | 599 | float amplitude=sqrt(pow(*forceXWorld,2)+pow(*forceYWorld,2)); |
Ludwigfr | 0:9f7ee7ed13e4 | 600 | if(amplitude!=0){//avoid division by 0 if forceX and forceY == 0 |
Ludwigfr | 0:9f7ee7ed13e4 | 601 | *forceXWorld=*forceXWorld/amplitude; |
Ludwigfr | 0:9f7ee7ed13e4 | 602 | *forceYWorld=*forceYWorld/amplitude; |
Ludwigfr | 3:37345c109dfc | 603 | }else{ |
Ludwigfr | 8:072a76960e27 | 604 | *forceXWorld=*forceXWorld/0.001; |
Ludwigfr | 8:072a76960e27 | 605 | *forceYWorld=*forceYWorld/0.001; |
Ludwigfr | 0:9f7ee7ed13e4 | 606 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 607 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 608 | |
Ludwigfr | 2:11cd5173aa36 | 609 | //for vff |
Ludwigfr | 0:9f7ee7ed13e4 | 610 | void MiniExplorerCoimbra::go_to_line(float line_a, float line_b, float line_c,float targetXWorld, float targetYWorld){ |
Ludwigfr | 0:9f7ee7ed13e4 | 611 | float lineAngle; |
Ludwigfr | 0:9f7ee7ed13e4 | 612 | float angleError; |
Ludwigfr | 0:9f7ee7ed13e4 | 613 | float linear; |
Ludwigfr | 0:9f7ee7ed13e4 | 614 | float angular; |
Ludwigfr | 2:11cd5173aa36 | 615 | float d; |
Ludwigfr | 0:9f7ee7ed13e4 | 616 | |
Ludwigfr | 0:9f7ee7ed13e4 | 617 | //line angle is beetween pi/2 and -pi/2 |
Ludwigfr | 2:11cd5173aa36 | 618 | |
Ludwigfr | 2:11cd5173aa36 | 619 | if(line_b!=0){ |
Ludwigfr | 2:11cd5173aa36 | 620 | lineAngle=atan(line_a/-line_b); |
Ludwigfr | 0:9f7ee7ed13e4 | 621 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 622 | else{ |
Ludwigfr | 3:37345c109dfc | 623 | lineAngle=0; |
Ludwigfr | 0:9f7ee7ed13e4 | 624 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 625 | |
Ludwigfr | 2:11cd5173aa36 | 626 | this->myOdometria(); |
Ludwigfr | 2:11cd5173aa36 | 627 | //Computing angle error |
Ludwigfr | 2:11cd5173aa36 | 628 | angleError = lineAngle-this->thetaWorld;//TODO that I m not sure |
Ludwigfr | 2:11cd5173aa36 | 629 | if(angleError>PI) |
Ludwigfr | 2:11cd5173aa36 | 630 | angleError=-(angleError-PI); |
Ludwigfr | 2:11cd5173aa36 | 631 | else |
Ludwigfr | 2:11cd5173aa36 | 632 | if(angleError<-PI) |
Ludwigfr | 2:11cd5173aa36 | 633 | angleError=-(angleError+PI); |
Ludwigfr | 2:11cd5173aa36 | 634 | |
Ludwigfr | 3:37345c109dfc | 635 | //d=this->distFromLine(this->xWorld, this->yWorld, line_a, line_b, line_c);//this could be 0 |
Ludwigfr | 3:37345c109dfc | 636 | d=0; |
Ludwigfr | 8:072a76960e27 | 637 | //pc.printf("\r\ndistance from line:%f",d); |
Ludwigfr | 0:9f7ee7ed13e4 | 638 | //Calculating velocities |
Ludwigfr | 2:11cd5173aa36 | 639 | linear= this->kv*(3.14); |
Ludwigfr | 2:11cd5173aa36 | 640 | angular=-this->kd*d + this->kh*angleError; |
Ludwigfr | 0:9f7ee7ed13e4 | 641 | |
Ludwigfr | 0:9f7ee7ed13e4 | 642 | float angularLeft=(linear-0.5*this->distanceWheels*angular)/this->radiusWheels; |
Ludwigfr | 2:11cd5173aa36 | 643 | float angularRight=(linear+0.5*this->distanceWheels*angular)/this->radiusWheels; |
Ludwigfr | 0:9f7ee7ed13e4 | 644 | |
Ludwigfr | 2:11cd5173aa36 | 645 | //Normalize speed for motors |
Ludwigfr | 0:9f7ee7ed13e4 | 646 | if(abs(angularLeft)>abs(angularRight)) { |
Ludwigfr | 0:9f7ee7ed13e4 | 647 | angularRight=this->speed*abs(angularRight/angularLeft)*this->sign1(angularRight); |
Ludwigfr | 0:9f7ee7ed13e4 | 648 | angularLeft=this->speed*this->sign1(angularLeft); |
Ludwigfr | 0:9f7ee7ed13e4 | 649 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 650 | else { |
Ludwigfr | 0:9f7ee7ed13e4 | 651 | angularLeft=this->speed*abs(angularLeft/angularRight)*this->sign1(angularLeft); |
Ludwigfr | 0:9f7ee7ed13e4 | 652 | angularRight=this->speed*this->sign1(angularRight); |
Ludwigfr | 0:9f7ee7ed13e4 | 653 | } |
Ludwigfr | 2:11cd5173aa36 | 654 | |
Ludwigfr | 2:11cd5173aa36 | 655 | pc.printf("\r\nd = %f", d); |
Ludwigfr | 3:37345c109dfc | 656 | pc.printf("\r\nerror = %f, lineAngle=%f, robotAngle=%f\n", angleError,lineAngle,this->thetaWorld); |
Ludwigfr | 2:11cd5173aa36 | 657 | |
Ludwigfr | 0:9f7ee7ed13e4 | 658 | leftMotor(this->sign2(angularLeft),abs(angularLeft)); |
Ludwigfr | 0:9f7ee7ed13e4 | 659 | rightMotor(this->sign2(angularRight),abs(angularRight)); |
Ludwigfr | 0:9f7ee7ed13e4 | 660 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 661 | |
geotsam | 1:20f48907c726 | 662 | void MiniExplorerCoimbra::go_to_line_first_lab(float line_a, float line_b, float line_c){ |
geotsam | 1:20f48907c726 | 663 | float lineAngle; |
geotsam | 1:20f48907c726 | 664 | float angleError; |
geotsam | 1:20f48907c726 | 665 | float linear; |
geotsam | 1:20f48907c726 | 666 | float angular; |
geotsam | 1:20f48907c726 | 667 | float d; |
geotsam | 1:20f48907c726 | 668 | |
geotsam | 1:20f48907c726 | 669 | //line angle is beetween pi/2 and -pi/2 |
geotsam | 1:20f48907c726 | 670 | |
geotsam | 1:20f48907c726 | 671 | if(line_b!=0){ |
geotsam | 1:20f48907c726 | 672 | lineAngle=atan(line_a/-line_b); |
geotsam | 1:20f48907c726 | 673 | } |
geotsam | 1:20f48907c726 | 674 | else{ |
geotsam | 1:20f48907c726 | 675 | lineAngle=1.5708; |
geotsam | 1:20f48907c726 | 676 | } |
geotsam | 1:20f48907c726 | 677 | |
geotsam | 1:20f48907c726 | 678 | do{ |
geotsam | 1:20f48907c726 | 679 | this->myOdometria(); |
geotsam | 1:20f48907c726 | 680 | //Computing angle error |
Ludwigfr | 3:37345c109dfc | 681 | pc.printf("\r\nline angle = %f", lineAngle); |
Ludwigfr | 3:37345c109dfc | 682 | pc.printf("\r\nthetaWorld = %f", thetaWorld); |
geotsam | 1:20f48907c726 | 683 | angleError = lineAngle-this->thetaWorld;//TODO that I m not sure |
geotsam | 1:20f48907c726 | 684 | |
Ludwigfr | 3:37345c109dfc | 685 | if(angleError>PI) |
Ludwigfr | 3:37345c109dfc | 686 | angleError=-(angleError-PI); |
Ludwigfr | 3:37345c109dfc | 687 | else |
Ludwigfr | 3:37345c109dfc | 688 | if(angleError<-PI) |
Ludwigfr | 3:37345c109dfc | 689 | angleError=-(angleError+PI); |
geotsam | 1:20f48907c726 | 690 | |
Ludwigfr | 3:37345c109dfc | 691 | pc.printf("\r\nangleError = %f\n", angleError); |
geotsam | 1:20f48907c726 | 692 | d=this->distFromLine(xWorld, yWorld, line_a, line_b, line_c); |
Ludwigfr | 3:37345c109dfc | 693 | pc.printf("\r\ndistance to line = %f", d); |
geotsam | 1:20f48907c726 | 694 | |
geotsam | 1:20f48907c726 | 695 | //Calculating velocities |
geotsam | 1:20f48907c726 | 696 | linear= this->kv*(3.14); |
geotsam | 1:20f48907c726 | 697 | angular=-this->kd*d + this->kh*angleError; |
geotsam | 1:20f48907c726 | 698 | |
geotsam | 1:20f48907c726 | 699 | float angularLeft=(linear-0.5*this->distanceWheels*angular)/this->radiusWheels; |
geotsam | 1:20f48907c726 | 700 | float angularRight=(linear+0.5*this->distanceWheels*angular)/this->radiusWheels; |
geotsam | 1:20f48907c726 | 701 | |
geotsam | 1:20f48907c726 | 702 | //Normalize speed for motors |
geotsam | 1:20f48907c726 | 703 | if(abs(angularLeft)>abs(angularRight)) { |
geotsam | 1:20f48907c726 | 704 | angularRight=this->speed*abs(angularRight/angularLeft)*this->sign1(angularRight); |
geotsam | 1:20f48907c726 | 705 | angularLeft=this->speed*this->sign1(angularLeft); |
geotsam | 1:20f48907c726 | 706 | } |
geotsam | 1:20f48907c726 | 707 | else { |
geotsam | 1:20f48907c726 | 708 | angularLeft=this->speed*abs(angularLeft/angularRight)*this->sign1(angularLeft); |
geotsam | 1:20f48907c726 | 709 | angularRight=this->speed*this->sign1(angularRight); |
geotsam | 1:20f48907c726 | 710 | } |
geotsam | 1:20f48907c726 | 711 | |
geotsam | 1:20f48907c726 | 712 | leftMotor(this->sign2(angularLeft),abs(angularLeft)); |
geotsam | 1:20f48907c726 | 713 | rightMotor(this->sign2(angularRight),abs(angularRight)); |
geotsam | 1:20f48907c726 | 714 | }while(1); |
geotsam | 1:20f48907c726 | 715 | } |
geotsam | 1:20f48907c726 | 716 | |
Ludwigfr | 0:9f7ee7ed13e4 | 717 | void MiniExplorerCoimbra::update_force(int widthIndice, int heightIndice, float* forceRepulsionComputedX, float* forceRepulsionComputedY ){ |
Ludwigfr | 0:9f7ee7ed13e4 | 718 | //get the coordonate of the map and the robot in the ortonormal space |
Ludwigfr | 0:9f7ee7ed13e4 | 719 | float xWorldCell=this->map.cell_width_coordinate_to_world(widthIndice); |
Ludwigfr | 0:9f7ee7ed13e4 | 720 | float yWorldCell=this->map.cell_height_coordinate_to_world(heightIndice); |
Ludwigfr | 0:9f7ee7ed13e4 | 721 | //compute the distance beetween the cell and the robot |
Ludwigfr | 0:9f7ee7ed13e4 | 722 | float distanceCellToRobot=sqrt(pow(xWorldCell-this->xWorld,2)+pow(yWorldCell-this->yWorld,2)); |
Ludwigfr | 3:37345c109dfc | 723 | float probaCell; |
Ludwigfr | 0:9f7ee7ed13e4 | 724 | //check if the cell is in range |
Ludwigfr | 8:072a76960e27 | 725 | //float anglePointToRobot=atan2(yWorldCell-this->yWorld,xWorldCell-this->xWorld);//like world system |
Ludwigfr | 3:37345c109dfc | 726 | float temp1; |
Ludwigfr | 3:37345c109dfc | 727 | float temp2; |
Ludwigfr | 0:9f7ee7ed13e4 | 728 | if(distanceCellToRobot <= this->rangeForce) { |
Ludwigfr | 3:37345c109dfc | 729 | probaCell=this->map.get_proba_cell(widthIndice,heightIndice); |
Ludwigfr | 8:072a76960e27 | 730 | //pc.printf("\r\nupdate force proba:%f",probaCell); |
Ludwigfr | 3:37345c109dfc | 731 | temp1=this->repulsionConstantForce*probaCell/pow(distanceCellToRobot,2); |
Ludwigfr | 3:37345c109dfc | 732 | temp2=(xWorldCell-this->xWorld)/distanceCellToRobot; |
Ludwigfr | 3:37345c109dfc | 733 | *forceRepulsionComputedX+=temp1*temp2; |
Ludwigfr | 3:37345c109dfc | 734 | temp2=(yWorldCell-this->yWorld)/distanceCellToRobot; |
Ludwigfr | 3:37345c109dfc | 735 | *forceRepulsionComputedY+=temp1*temp2; |
Ludwigfr | 0:9f7ee7ed13e4 | 736 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 737 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 738 | |
Ludwigfr | 0:9f7ee7ed13e4 | 739 | //return 1 if positiv, -1 if negativ |
Ludwigfr | 0:9f7ee7ed13e4 | 740 | float MiniExplorerCoimbra::sign1(float value){ |
Ludwigfr | 0:9f7ee7ed13e4 | 741 | if(value>=0) |
Ludwigfr | 0:9f7ee7ed13e4 | 742 | return 1; |
Ludwigfr | 0:9f7ee7ed13e4 | 743 | else |
Ludwigfr | 0:9f7ee7ed13e4 | 744 | return -1; |
Ludwigfr | 0:9f7ee7ed13e4 | 745 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 746 | |
Ludwigfr | 0:9f7ee7ed13e4 | 747 | //return 1 if positiv, 0 if negativ |
Ludwigfr | 0:9f7ee7ed13e4 | 748 | int MiniExplorerCoimbra::sign2(float value){ |
Ludwigfr | 0:9f7ee7ed13e4 | 749 | if(value>=0) |
Ludwigfr | 0:9f7ee7ed13e4 | 750 | return 1; |
Ludwigfr | 0:9f7ee7ed13e4 | 751 | else |
Ludwigfr | 0:9f7ee7ed13e4 | 752 | return 0; |
Ludwigfr | 0:9f7ee7ed13e4 | 753 | } |
Ludwigfr | 0:9f7ee7ed13e4 | 754 | |
geotsam | 1:20f48907c726 | 755 | float MiniExplorerCoimbra::distFromLine(float robot_x, float robot_y, float line_a, float line_b, float line_c){ |
geotsam | 1:20f48907c726 | 756 | return abs((line_a*robot_x+line_b*robot_y+line_c)/sqrt(line_a*line_a+line_b*line_b)); |
geotsam | 1:20f48907c726 | 757 | } |
geotsam | 1:20f48907c726 | 758 | |
Ludwigfr | 5:19f24c363418 | 759 | //4th LAB |
Ludwigfr | 5:19f24c363418 | 760 | //starting position lower left |
Ludwigfr | 5:19f24c363418 | 761 | |
Ludwigfr | 10:d0109d7cbe7c | 762 | void MiniExplorerCoimbra::test_procedure_lab_4(float sizeX, float sizeY){ |
Ludwigfr | 5:19f24c363418 | 763 | |
Ludwigfr | 5:19f24c363418 | 764 | this->map.fill_map_with_kalman_knowledge(); |
Ludwigfr | 10:d0109d7cbe7c | 765 | this->go_to_point_kalman(this->xWorld+sizeX,this->yWorld+sizeY); |
Ludwigfr | 5:19f24c363418 | 766 | } |
Ludwigfr | 5:19f24c363418 | 767 | |
Ludwigfr | 5:19f24c363418 | 768 | //move of targetXWorld and targetYWorld ending in a targetAngleWorld |
Ludwigfr | 5:19f24c363418 | 769 | void MiniExplorerCoimbra::go_turn_kalman(float targetXWorld, float targetYWorld, float targetAngleWorld) { |
Ludwigfr | 5:19f24c363418 | 770 | //make sure the target is correct |
Ludwigfr | 5:19f24c363418 | 771 | if(targetAngleWorld > PI) |
Ludwigfr | 5:19f24c363418 | 772 | targetAngleWorld=-2*PI+targetAngleWorld; |
Ludwigfr | 5:19f24c363418 | 773 | if(targetAngleWorld < -PI) |
Ludwigfr | 5:19f24c363418 | 774 | targetAngleWorld=2*PI+targetAngleWorld; |
Ludwigfr | 5:19f24c363418 | 775 | |
Ludwigfr | 5:19f24c363418 | 776 | float distanceToTarget=100; |
Ludwigfr | 5:19f24c363418 | 777 | do { |
Ludwigfr | 5:19f24c363418 | 778 | leftMotor(1,50); |
Ludwigfr | 5:19f24c363418 | 779 | rightMotor(0,50); |
Ludwigfr | 10:d0109d7cbe7c | 780 | pc.printf("\r\n test lab 4: OdometriaKalmanFilter"); |
Ludwigfr | 6:0e8db3a23486 | 781 | this->OdometriaKalmanFilter(); |
Ludwigfr | 5:19f24c363418 | 782 | |
Ludwigfr | 5:19f24c363418 | 783 | float distanceToTarget=this->dist(this->xWorld, this->yWorld, targetXWorld, targetYWorld); |
Ludwigfr | 5:19f24c363418 | 784 | //pc.printf("\n\rdist to target= %f",distanceToTarget); |
Ludwigfr | 5:19f24c363418 | 785 | |
Ludwigfr | 5:19f24c363418 | 786 | } while(distanceToTarget>1 || (abs(targetAngleWorld-this->thetaWorld)>0.1)); |
Ludwigfr | 5:19f24c363418 | 787 | |
Ludwigfr | 5:19f24c363418 | 788 | //Stop at the end |
Ludwigfr | 5:19f24c363418 | 789 | leftMotor(1,0); |
Ludwigfr | 5:19f24c363418 | 790 | rightMotor(1,0); |
Ludwigfr | 5:19f24c363418 | 791 | pc.printf("\r\nReached Target!"); |
Ludwigfr | 5:19f24c363418 | 792 | } |
Ludwigfr | 5:19f24c363418 | 793 | |
Ludwigfr | 5:19f24c363418 | 794 | //move of targetXWorld and targetYWorld ending in a targetAngleWorld |
Ludwigfr | 5:19f24c363418 | 795 | void MiniExplorerCoimbra::go_straight_kalman(float targetXWorld, float targetYWorld, float targetAngleWorld) { |
Ludwigfr | 5:19f24c363418 | 796 | //make sure the target is correct |
Ludwigfr | 5:19f24c363418 | 797 | if(targetAngleWorld > PI) |
Ludwigfr | 5:19f24c363418 | 798 | targetAngleWorld=-2*PI+targetAngleWorld; |
Ludwigfr | 5:19f24c363418 | 799 | if(targetAngleWorld < -PI) |
Ludwigfr | 5:19f24c363418 | 800 | targetAngleWorld=2*PI+targetAngleWorld; |
Ludwigfr | 5:19f24c363418 | 801 | |
Ludwigfr | 5:19f24c363418 | 802 | float distanceToTarget=100;; |
Ludwigfr | 5:19f24c363418 | 803 | |
Ludwigfr | 5:19f24c363418 | 804 | do { |
Ludwigfr | 5:19f24c363418 | 805 | leftMotor(1,400); |
Ludwigfr | 5:19f24c363418 | 806 | rightMotor(1,400); |
Ludwigfr | 6:0e8db3a23486 | 807 | this->OdometriaKalmanFilter(); |
Ludwigfr | 5:19f24c363418 | 808 | |
Ludwigfr | 5:19f24c363418 | 809 | float distanceToTarget=this->dist(this->xWorld, this->yWorld, targetXWorld, targetYWorld); |
Ludwigfr | 5:19f24c363418 | 810 | pc.printf("\n\rdist to target= %f",distanceToTarget); |
Ludwigfr | 5:19f24c363418 | 811 | |
Ludwigfr | 5:19f24c363418 | 812 | } while(distanceToTarget>1 || (abs(targetAngleWorld-this->thetaWorld)>0.1)); |
Ludwigfr | 5:19f24c363418 | 813 | |
Ludwigfr | 5:19f24c363418 | 814 | //Stop at the end |
Ludwigfr | 5:19f24c363418 | 815 | leftMotor(1,0); |
Ludwigfr | 5:19f24c363418 | 816 | rightMotor(1,0); |
Ludwigfr | 5:19f24c363418 | 817 | pc.printf("\r\nReached Target!"); |
Ludwigfr | 5:19f24c363418 | 818 | } |
Ludwigfr | 5:19f24c363418 | 819 | |
Ludwigfr | 10:d0109d7cbe7c | 820 | void MiniExplorerCoimbra::OdometriaKalmanFilter(){ |
Ludwigfr | 13:b0ddd71e8f08 | 821 | float encoderRightFailureRate=1; |
Ludwigfr | 13:b0ddd71e8f08 | 822 | float encoderLeftFailureRate=1; |
Ludwigfr | 13:b0ddd71e8f08 | 823 | int skip=1;//1==skip Kalman correction, just use KINEMATICS |
Ludwigfr | 10:d0109d7cbe7c | 824 | //=====KINEMATICS=========================== |
Ludwigfr | 13:b0ddd71e8f08 | 825 | //we have trouble reading the encoders, in many case we only get 0 |
Ludwigfr | 13:b0ddd71e8f08 | 826 | float R_cmK; |
Ludwigfr | 13:b0ddd71e8f08 | 827 | float L_cmK; |
Ludwigfr | 13:b0ddd71e8f08 | 828 | /* |
Ludwigfr | 12:1e80471c5c6c | 829 | long int ticks1d=R_encoder(); |
Ludwigfr | 12:1e80471c5c6c | 830 | |
Ludwigfr | 12:1e80471c5c6c | 831 | char data_r_2[5]; |
Ludwigfr | 12:1e80471c5c6c | 832 | |
Ludwigfr | 12:1e80471c5c6c | 833 | i2c1.start(); |
Ludwigfr | 12:1e80471c5c6c | 834 | i2c1.write(0x6C); |
Ludwigfr | 12:1e80471c5c6c | 835 | i2c1.write(0x0C); |
Ludwigfr | 12:1e80471c5c6c | 836 | i2c1.read(0x6D,data_r_2,4,0); |
Ludwigfr | 12:1e80471c5c6c | 837 | i2c1.stop(); |
Ludwigfr | 12:1e80471c5c6c | 838 | |
Ludwigfr | 12:1e80471c5c6c | 839 | short int val1=data_r_2[0]; |
Ludwigfr | 12:1e80471c5c6c | 840 | short int val2=data_r_2[1]; |
Ludwigfr | 12:1e80471c5c6c | 841 | val1=(val1&0xf)*256; |
Ludwigfr | 12:1e80471c5c6c | 842 | long int final=(val2+val1); |
Ludwigfr | 12:1e80471c5c6c | 843 | |
Ludwigfr | 12:1e80471c5c6c | 844 | ticks1d=final; |
Ludwigfr | 12:1e80471c5c6c | 845 | |
Ludwigfr | 12:1e80471c5c6c | 846 | long int ticks1e=L_encoder(); |
Ludwigfr | 12:1e80471c5c6c | 847 | |
Ludwigfr | 12:1e80471c5c6c | 848 | char data_r_2_2[5]; |
Ludwigfr | 5:19f24c363418 | 849 | |
Ludwigfr | 12:1e80471c5c6c | 850 | i2c.start(); |
Ludwigfr | 12:1e80471c5c6c | 851 | i2c.write(0x6C); |
Ludwigfr | 12:1e80471c5c6c | 852 | i2c.write(0x0C); |
Ludwigfr | 12:1e80471c5c6c | 853 | i2c.read(0x6D,data_r_2_2,4,0); |
Ludwigfr | 12:1e80471c5c6c | 854 | i2c.stop(); |
Ludwigfr | 12:1e80471c5c6c | 855 | |
Ludwigfr | 12:1e80471c5c6c | 856 | val1=data_r_2_2[0]; |
Ludwigfr | 12:1e80471c5c6c | 857 | val2=data_r_2_2[1]; |
Ludwigfr | 12:1e80471c5c6c | 858 | val1=(val1&0xf)*256; |
Ludwigfr | 12:1e80471c5c6c | 859 | final=(val2+val1); |
Ludwigfr | 12:1e80471c5c6c | 860 | |
Ludwigfr | 12:1e80471c5c6c | 861 | ticks1e= final; |
Ludwigfr | 12:1e80471c5c6c | 862 | |
Ludwigfr | 12:1e80471c5c6c | 863 | pc.printf("\r\nEncoders ticks1d:%d,ticks1e:%d",ticks1d,ticks1e); |
Ludwigfr | 12:1e80471c5c6c | 864 | |
Ludwigfr | 12:1e80471c5c6c | 865 | long int R_ticks=ticks1d - ticks2d; |
Ludwigfr | 12:1e80471c5c6c | 866 | long int L_ticks=ticks1e - ticks2e; |
Ludwigfr | 12:1e80471c5c6c | 867 | |
Ludwigfr | 12:1e80471c5c6c | 868 | pc.printf("\r\nEncoders R_ticks:%d,L_ticks:%d",R_ticks,L_ticks); |
Ludwigfr | 12:1e80471c5c6c | 869 | //robot.h |
Ludwigfr | 12:1e80471c5c6c | 870 | ticks2d=ticks1d; |
Ludwigfr | 12:1e80471c5c6c | 871 | ticks2e=ticks1e; |
Ludwigfr | 13:b0ddd71e8f08 | 872 | |
Ludwigfr | 13:b0ddd71e8f08 | 873 | R_cmK= (float)R_ticks*((3.25*3.1415)/4096); |
Ludwigfr | 13:b0ddd71e8f08 | 874 | L_cmK= (float)L_ticks*((3.25*3.1415)/4096); |
Ludwigfr | 13:b0ddd71e8f08 | 875 | */ |
Ludwigfr | 13:b0ddd71e8f08 | 876 | //fill R_cmK and L_cmK with how much is wheel has moved (custom robot.h) |
Ludwigfr | 13:b0ddd71e8f08 | 877 | OdometriaKalman(&R_cmK, &L_cmK); |
Ludwigfr | 12:1e80471c5c6c | 878 | //Odometria(); |
Ludwigfr | 13:b0ddd71e8f08 | 879 | |
Ludwigfr | 12:1e80471c5c6c | 880 | R_cmK= encoderRightFailureRate*R_cmK; |
Ludwigfr | 12:1e80471c5c6c | 881 | L_cmK= encoderLeftFailureRate*L_cmK; |
Ludwigfr | 12:1e80471c5c6c | 882 | //float R_cmK=D_cm*encoderRightFailureRate; |
Ludwigfr | 12:1e80471c5c6c | 883 | //float L_cmK=L_cm*encoderLeftFailureRate; |
Ludwigfr | 12:1e80471c5c6c | 884 | |
Ludwigfr | 12:1e80471c5c6c | 885 | pc.printf("\r\nEncoders R_cm:%f,L_cm:%f",R_cmK,L_cmK); |
Ludwigfr | 5:19f24c363418 | 886 | |
Ludwigfr | 12:1e80471c5c6c | 887 | float distanceMoved=(R_cmK+L_cmK)/2; |
Ludwigfr | 12:1e80471c5c6c | 888 | float angleMoved=(R_cmK-L_cmK)/this->distanceWheels; |
Ludwigfr | 12:1e80471c5c6c | 889 | angleMoved = atan2(sin(angleMoved), cos(angleMoved)); |
Ludwigfr | 12:1e80471c5c6c | 890 | |
Ludwigfr | 13:b0ddd71e8f08 | 891 | //this->thetaWorld to theta robot |
Ludwigfr | 12:1e80471c5c6c | 892 | float currTheta; |
Ludwigfr | 12:1e80471c5c6c | 893 | if(this->thetaWorld < -PI/2) |
Ludwigfr | 12:1e80471c5c6c | 894 | currTheta=PI/2+PI-this->thetaWorld; |
Ludwigfr | 12:1e80471c5c6c | 895 | else |
Ludwigfr | 12:1e80471c5c6c | 896 | currTheta=this->thetaWorld-PI/2; |
Ludwigfr | 13:b0ddd71e8f08 | 897 | |
Ludwigfr | 12:1e80471c5c6c | 898 | currTheta=currTheta+angleMoved; |
Ludwigfr | 12:1e80471c5c6c | 899 | currTheta = atan2(sin(currTheta), cos(currTheta)); |
Ludwigfr | 13:b0ddd71e8f08 | 900 | |
Ludwigfr | 13:b0ddd71e8f08 | 901 | //currTheta to world coordinates |
Ludwigfr | 12:1e80471c5c6c | 902 | float newAngleThetaWorld; |
Ludwigfr | 12:1e80471c5c6c | 903 | if(currTheta >PI/2) |
Ludwigfr | 12:1e80471c5c6c | 904 | newAngleThetaWorld=-PI+(currTheta-PI/2); |
Ludwigfr | 12:1e80471c5c6c | 905 | else |
Ludwigfr | 12:1e80471c5c6c | 906 | newAngleThetaWorld=currTheta+PI/2; |
Ludwigfr | 12:1e80471c5c6c | 907 | //compute difference with cur angle |
Ludwigfr | 12:1e80471c5c6c | 908 | angleMoved = newAngleThetaWorld-this->thetaWorld; |
Ludwigfr | 12:1e80471c5c6c | 909 | if(angleMoved>PI) |
Ludwigfr | 12:1e80471c5c6c | 910 | angleMoved=-(angleMoved-PI); |
Ludwigfr | 12:1e80471c5c6c | 911 | else |
Ludwigfr | 12:1e80471c5c6c | 912 | if(angleMoved<-PI) |
Ludwigfr | 12:1e80471c5c6c | 913 | angleMoved=-(angleMoved+PI); |
Ludwigfr | 5:19f24c363418 | 914 | |
Ludwigfr | 12:1e80471c5c6c | 915 | pc.printf("\r\ndistanceMoved:%f, angleMoved:%f, totalAngle:%f",distanceMoved,angleMoved,newAngleThetaWorld); |
Ludwigfr | 12:1e80471c5c6c | 916 | //here testing with robot coordinates |
Ludwigfr | 12:1e80471c5c6c | 917 | float distanceMovedX=distanceMoved*cos(this->thetaWorld+(R_cmK-L_cmK)/(2*this->distanceWheels)); |
Ludwigfr | 12:1e80471c5c6c | 918 | float distanceMovedY=distanceMoved*sin(this->thetaWorld+(R_cmK-L_cmK)/(2*this->distanceWheels)); |
Ludwigfr | 12:1e80471c5c6c | 919 | pc.printf("\r\ndistanceMovedX:%f, distanceMovedY:%f",distanceMovedX,distanceMovedY); |
Ludwigfr | 5:19f24c363418 | 920 | |
Ludwigfr | 5:19f24c363418 | 921 | //try with world coordinate system |
Ludwigfr | 10:d0109d7cbe7c | 922 | |
Ludwigfr | 9:1cc27f33d3e1 | 923 | myMatrix poseKplus1K(3,1); |
Ludwigfr | 9:1cc27f33d3e1 | 924 | poseKplus1K.data[0][0]=this->xWorld+distanceMovedX; |
Ludwigfr | 9:1cc27f33d3e1 | 925 | poseKplus1K.data[1][0]=this->yWorld+distanceMovedY; |
Ludwigfr | 13:b0ddd71e8f08 | 926 | //poseKplus1K.data[2][0]=this->thetaWorld+angleMoved; |
Ludwigfr | 13:b0ddd71e8f08 | 927 | poseKplus1K.data[2][0]=newAngleThetaWorld; |
Ludwigfr | 13:b0ddd71e8f08 | 928 | //note if the encoders are correct it should work |
Ludwigfr | 12:1e80471c5c6c | 929 | pc.printf("\r\nWithout correction: X=%f, Y=%f, theta=%f",poseKplus1K.get(0,0),poseKplus1K.get(1,0),poseKplus1K.get(2,0)); |
Ludwigfr | 6:0e8db3a23486 | 930 | //=====ERROR_MODEL=========================== |
Ludwigfr | 6:0e8db3a23486 | 931 | |
Ludwigfr | 11:b91fe0ed4fed | 932 | //FP Matrix slide LocalizationKALMAN |
Ludwigfr | 9:1cc27f33d3e1 | 933 | myMatrix Fp(3,3); |
Ludwigfr | 9:1cc27f33d3e1 | 934 | Fp.data[0][0]=1; |
Ludwigfr | 9:1cc27f33d3e1 | 935 | Fp.data[1][1]=1; |
Ludwigfr | 9:1cc27f33d3e1 | 936 | Fp.data[2][2]=1; |
Ludwigfr | 9:1cc27f33d3e1 | 937 | Fp.data[0][2]=-1*distanceMoved*sin(this->thetaWorld+(angleMoved/2)); |
Ludwigfr | 9:1cc27f33d3e1 | 938 | Fp.data[1][2]=distanceMoved*cos(this->thetaWorld+(angleMoved/2)); |
Ludwigfr | 9:1cc27f33d3e1 | 939 | |
Ludwigfr | 9:1cc27f33d3e1 | 940 | myMatrix FpTranspose(3,3); |
Ludwigfr | 9:1cc27f33d3e1 | 941 | FpTranspose.fillWithTranspose(Fp); |
Ludwigfr | 9:1cc27f33d3e1 | 942 | |
Ludwigfr | 11:b91fe0ed4fed | 943 | //Frl matrix slide LocalizationKALMAN |
Ludwigfr | 9:1cc27f33d3e1 | 944 | myMatrix Frl(3,2); |
Ludwigfr | 9:1cc27f33d3e1 | 945 | Frl.data[0][0]=0.5*cos(this->thetaWorld+(angleMoved/2))-(distanceMoved/(2*this->distanceWheels))*sin(this->thetaWorld+(angleMoved/2)); |
Ludwigfr | 9:1cc27f33d3e1 | 946 | Frl.data[0][1]=0.5*cos(this->thetaWorld+(angleMoved/2))+(distanceMoved/(2*this->distanceWheels))*sin(this->thetaWorld+(angleMoved/2)); |
Ludwigfr | 9:1cc27f33d3e1 | 947 | Frl.data[1][0]=0.5*sin(this->thetaWorld+(angleMoved/2))+(distanceMoved/(2*this->distanceWheels))*cos(this->thetaWorld+(angleMoved/2)); |
Ludwigfr | 9:1cc27f33d3e1 | 948 | Frl.data[1][1]=0.5*sin(this->thetaWorld+(angleMoved/2))-(distanceMoved/(2*this->distanceWheels))*cos(this->thetaWorld+(angleMoved/2)); |
Ludwigfr | 9:1cc27f33d3e1 | 949 | Frl.data[2][0]=(1/this->distanceWheels); |
Ludwigfr | 9:1cc27f33d3e1 | 950 | Frl.data[2][1]=-(1/this->distanceWheels) ; |
Ludwigfr | 9:1cc27f33d3e1 | 951 | |
Ludwigfr | 9:1cc27f33d3e1 | 952 | myMatrix FrlTranspose(2,3); |
Ludwigfr | 9:1cc27f33d3e1 | 953 | FrlTranspose.fillWithTranspose(Frl); |
Ludwigfr | 9:1cc27f33d3e1 | 954 | |
Ludwigfr | 6:0e8db3a23486 | 955 | //error constants... |
Ludwigfr | 6:0e8db3a23486 | 956 | float kr=1; |
Ludwigfr | 6:0e8db3a23486 | 957 | float kl=1; |
Ludwigfr | 9:1cc27f33d3e1 | 958 | myMatrix covar(2,2); |
Ludwigfr | 12:1e80471c5c6c | 959 | covar.data[0][0]=kr*abs(R_cmK); |
Ludwigfr | 12:1e80471c5c6c | 960 | covar.data[1][1]=kl*abs(L_cmK); |
Ludwigfr | 6:0e8db3a23486 | 961 | |
Ludwigfr | 6:0e8db3a23486 | 962 | //uncertainty positionx, and theta at |
Ludwigfr | 6:0e8db3a23486 | 963 | //1,1,1 |
Ludwigfr | 9:1cc27f33d3e1 | 964 | myMatrix Q(3,3); |
Ludwigfr | 9:1cc27f33d3e1 | 965 | Q.data[0][0]=1; |
Ludwigfr | 9:1cc27f33d3e1 | 966 | Q.data[1][1]=2; |
Ludwigfr | 9:1cc27f33d3e1 | 967 | Q.data[2][2]=0.01; |
Ludwigfr | 9:1cc27f33d3e1 | 968 | |
Ludwigfr | 11:b91fe0ed4fed | 969 | //new covariance= Fp*old covariance*FpTranspose +Frl*covar*FrlTranspose +Q slide LocalizationKALMAN |
Ludwigfr | 9:1cc27f33d3e1 | 970 | myMatrix covariancePositionEstimationKplus1K(3,3); |
Ludwigfr | 9:1cc27f33d3e1 | 971 | myMatrix temp1(3,3); |
Ludwigfr | 9:1cc27f33d3e1 | 972 | temp1.fillByMultiplication(Fp,this->covariancePositionEstimationK);//Fp*old covariance |
Ludwigfr | 9:1cc27f33d3e1 | 973 | myMatrix temp2(3,3); |
Ludwigfr | 9:1cc27f33d3e1 | 974 | temp2.fillByMultiplication(temp1,FpTranspose);//Fp*old covariance*FpTranspose |
Ludwigfr | 9:1cc27f33d3e1 | 975 | temp1.fillWithZeroes(); |
Ludwigfr | 9:1cc27f33d3e1 | 976 | myMatrix temp3(3,2); |
Ludwigfr | 9:1cc27f33d3e1 | 977 | temp3.fillByMultiplication(Frl,covar);//Frl*covar |
Ludwigfr | 9:1cc27f33d3e1 | 978 | temp1.fillByMultiplication(temp3,FrlTranspose);//Frl*covar*FrlTranspose |
Ludwigfr | 9:1cc27f33d3e1 | 979 | |
Ludwigfr | 9:1cc27f33d3e1 | 980 | covariancePositionEstimationKplus1K.addition(temp2);//Fp*old covariance*FpTranspose |
Ludwigfr | 9:1cc27f33d3e1 | 981 | covariancePositionEstimationKplus1K.addition(temp1);//Fp*old covariance*FpTranspose +Frl*covar*FrlTranspose |
Ludwigfr | 9:1cc27f33d3e1 | 982 | covariancePositionEstimationKplus1K.addition(Q);//Fp*old covariance*FpTranspose +Frl*covar*FrlTranspose +Q |
Ludwigfr | 12:1e80471c5c6c | 983 | |
Ludwigfr | 12:1e80471c5c6c | 984 | if(skip==1){ |
Ludwigfr | 12:1e80471c5c6c | 985 | this->covariancePositionEstimationK.fillByCopy(covariancePositionEstimationKplus1K); |
Ludwigfr | 12:1e80471c5c6c | 986 | |
Ludwigfr | 12:1e80471c5c6c | 987 | //pc.printf("\r\nposeKplus1Kplus1 X=%f, Y=%f, theta=%f",poseKplus1Kplus1.data[0][0],poseKplus1Kplus1.data[1][0],poseKplus1Kplus1.data[2][0]); |
Ludwigfr | 12:1e80471c5c6c | 988 | //update pose |
Ludwigfr | 12:1e80471c5c6c | 989 | this->xWorld=poseKplus1K.data[0][0]; |
Ludwigfr | 12:1e80471c5c6c | 990 | this->yWorld=poseKplus1K.data[1][0]; |
Ludwigfr | 12:1e80471c5c6c | 991 | this->thetaWorld=poseKplus1K.data[2][0]; |
Ludwigfr | 12:1e80471c5c6c | 992 | |
Ludwigfr | 12:1e80471c5c6c | 993 | pc.printf("\r\nWithout Kalman X=%f, Y=%f, theta=%f",xWorld,yWorld,thetaWorld); |
Ludwigfr | 12:1e80471c5c6c | 994 | }else{ |
Ludwigfr | 12:1e80471c5c6c | 995 | //=====OBSERVATION===== |
Ludwigfr | 12:1e80471c5c6c | 996 | //get the estimated measure we should have according to our knowledge of the map and the previously computed localisation |
Ludwigfr | 12:1e80471c5c6c | 997 | |
Ludwigfr | 12:1e80471c5c6c | 998 | float leftCmEstimated=this->sonarLeft.maxRange; |
Ludwigfr | 12:1e80471c5c6c | 999 | float frontCmEstimated=this->sonarFront.maxRange; |
Ludwigfr | 12:1e80471c5c6c | 1000 | float rightCmEstimated=this->sonarRight.maxRange; |
Ludwigfr | 12:1e80471c5c6c | 1001 | float xWorldCell; |
Ludwigfr | 12:1e80471c5c6c | 1002 | float yWorldCell; |
Ludwigfr | 12:1e80471c5c6c | 1003 | float currDistance; |
Ludwigfr | 12:1e80471c5c6c | 1004 | float xClosestCellLeft; |
Ludwigfr | 12:1e80471c5c6c | 1005 | float yClosestCellLeft; |
Ludwigfr | 12:1e80471c5c6c | 1006 | float xClosestCellFront; |
Ludwigfr | 12:1e80471c5c6c | 1007 | float yClosestCellFront; |
Ludwigfr | 12:1e80471c5c6c | 1008 | float xClosestCellRight; |
Ludwigfr | 12:1e80471c5c6c | 1009 | float yClosestCellRight; |
Ludwigfr | 12:1e80471c5c6c | 1010 | |
Ludwigfr | 12:1e80471c5c6c | 1011 | //note: sonar.isInRange already incorpore the sonar position and angle relative to the robot |
Ludwigfr | 12:1e80471c5c6c | 1012 | //note curr change to isInRange: xs-xcell and not xcell-xs |
Ludwigfr | 12:1e80471c5c6c | 1013 | //get theorical distance to sonar |
Ludwigfr | 12:1e80471c5c6c | 1014 | for(int i=0;i<this->map.nbCellWidth;i++){ |
Ludwigfr | 12:1e80471c5c6c | 1015 | for(int j=0;j<this->map.nbCellHeight;j++){ |
Ludwigfr | 12:1e80471c5c6c | 1016 | //check if occupied, if not discard |
Ludwigfr | 12:1e80471c5c6c | 1017 | if(this->map.get_proba_cell(i,j)>0.5){ |
Ludwigfr | 12:1e80471c5c6c | 1018 | //check if in sonar range |
Ludwigfr | 12:1e80471c5c6c | 1019 | xWorldCell=this->map.cell_width_coordinate_to_world(i); |
Ludwigfr | 12:1e80471c5c6c | 1020 | yWorldCell=this->map.cell_height_coordinate_to_world(j); |
Ludwigfr | 12:1e80471c5c6c | 1021 | //check left |
Ludwigfr | 12:1e80471c5c6c | 1022 | currDistance=this->sonarLeft.isInRange(xWorldCell,yWorldCell,poseKplus1K.data[0][0],poseKplus1K.data[1][0],poseKplus1K.data[2][0]); |
Ludwigfr | 12:1e80471c5c6c | 1023 | if((currDistance < this->sonarLeft.maxRange) && currDistance > -1){ |
Ludwigfr | 12:1e80471c5c6c | 1024 | //check if distance is lower than previous, update lowest if so |
Ludwigfr | 12:1e80471c5c6c | 1025 | if(currDistance < leftCmEstimated){ |
Ludwigfr | 12:1e80471c5c6c | 1026 | leftCmEstimated= currDistance; |
Ludwigfr | 12:1e80471c5c6c | 1027 | xClosestCellLeft=xWorldCell; |
Ludwigfr | 12:1e80471c5c6c | 1028 | yClosestCellLeft=yWorldCell; |
Ludwigfr | 12:1e80471c5c6c | 1029 | } |
Ludwigfr | 12:1e80471c5c6c | 1030 | } |
Ludwigfr | 12:1e80471c5c6c | 1031 | //check front |
Ludwigfr | 12:1e80471c5c6c | 1032 | currDistance=this->sonarFront.isInRange(xWorldCell,yWorldCell,poseKplus1K.data[0][0],poseKplus1K.data[1][0],poseKplus1K.data[2][0]); |
Ludwigfr | 12:1e80471c5c6c | 1033 | if((currDistance < this->sonarFront.maxRange) && currDistance > -1){ |
Ludwigfr | 12:1e80471c5c6c | 1034 | //check if distance is lower than previous, update lowest if so |
Ludwigfr | 12:1e80471c5c6c | 1035 | if(currDistance < frontCmEstimated){ |
Ludwigfr | 12:1e80471c5c6c | 1036 | frontCmEstimated= currDistance; |
Ludwigfr | 12:1e80471c5c6c | 1037 | xClosestCellFront=xWorldCell; |
Ludwigfr | 12:1e80471c5c6c | 1038 | yClosestCellFront=yWorldCell; |
Ludwigfr | 12:1e80471c5c6c | 1039 | } |
Ludwigfr | 12:1e80471c5c6c | 1040 | } |
Ludwigfr | 12:1e80471c5c6c | 1041 | //check right |
Ludwigfr | 12:1e80471c5c6c | 1042 | currDistance=this->sonarRight.isInRange(xWorldCell,yWorldCell,poseKplus1K.data[0][0],poseKplus1K.data[1][0],poseKplus1K.data[2][0]); |
Ludwigfr | 12:1e80471c5c6c | 1043 | if((currDistance < this->sonarRight.maxRange) && currDistance > -1){ |
Ludwigfr | 12:1e80471c5c6c | 1044 | //check if distance is lower than previous, update lowest if so |
Ludwigfr | 12:1e80471c5c6c | 1045 | if(currDistance < rightCmEstimated){ |
Ludwigfr | 12:1e80471c5c6c | 1046 | rightCmEstimated= currDistance; |
Ludwigfr | 12:1e80471c5c6c | 1047 | xClosestCellRight=xWorldCell; |
Ludwigfr | 12:1e80471c5c6c | 1048 | yClosestCellRight=yWorldCell; |
Ludwigfr | 12:1e80471c5c6c | 1049 | } |
Ludwigfr | 12:1e80471c5c6c | 1050 | } |
Ludwigfr | 12:1e80471c5c6c | 1051 | } |
Ludwigfr | 12:1e80471c5c6c | 1052 | } |
Ludwigfr | 12:1e80471c5c6c | 1053 | } |
Ludwigfr | 9:1cc27f33d3e1 | 1054 | |
Ludwigfr | 12:1e80471c5c6c | 1055 | //check measurements from sonars, see if they passed the validation gate |
Ludwigfr | 12:1e80471c5c6c | 1056 | float leftCm = get_distance_left_sensor()/10; |
Ludwigfr | 12:1e80471c5c6c | 1057 | float frontCm = get_distance_front_sensor()/10; |
Ludwigfr | 12:1e80471c5c6c | 1058 | float rightCm = get_distance_right_sensor()/10; |
Ludwigfr | 12:1e80471c5c6c | 1059 | |
Ludwigfr | 12:1e80471c5c6c | 1060 | //if superior to sonar range, put the value to sonar max range |
Ludwigfr | 12:1e80471c5c6c | 1061 | if(leftCm > this->sonarLeft.maxRange) |
Ludwigfr | 12:1e80471c5c6c | 1062 | leftCm=this->sonarLeft.maxRange; |
Ludwigfr | 12:1e80471c5c6c | 1063 | if(frontCm > this->sonarFront.maxRange) |
Ludwigfr | 12:1e80471c5c6c | 1064 | frontCm=this->sonarFront.maxRange; |
Ludwigfr | 12:1e80471c5c6c | 1065 | if(rightCm > this->sonarRight.maxRange) |
Ludwigfr | 12:1e80471c5c6c | 1066 | rightCm=this->sonarRight.maxRange; |
Ludwigfr | 12:1e80471c5c6c | 1067 | |
Ludwigfr | 12:1e80471c5c6c | 1068 | pc.printf("\r\ndistance sonars read Lcm=%f, FCm=%f, RCm=%f",leftCm,frontCm,rightCm); |
Ludwigfr | 12:1e80471c5c6c | 1069 | pc.printf("\r\ndistance sonars estimated ELcm=%f, EFCm=%f, ERCm=%f",leftCmEstimated,frontCmEstimated,rightCmEstimated); |
Ludwigfr | 9:1cc27f33d3e1 | 1070 | |
Ludwigfr | 12:1e80471c5c6c | 1071 | //======INNOVATION======== |
Ludwigfr | 12:1e80471c5c6c | 1072 | //compute jacobian of observation |
Ludwigfr | 12:1e80471c5c6c | 1073 | myMatrix jacobianOfObservationLeft(1,3); |
Ludwigfr | 12:1e80471c5c6c | 1074 | myMatrix jacobianOfObservationRight(1,3); |
Ludwigfr | 12:1e80471c5c6c | 1075 | myMatrix jacobianOfObservationFront(1,3); |
Ludwigfr | 12:1e80471c5c6c | 1076 | |
Ludwigfr | 12:1e80471c5c6c | 1077 | //(5) |
Ludwigfr | 13:b0ddd71e8f08 | 1078 | //note: for cos/sin having abs(angles) > PI is not an issue |
Ludwigfr | 12:1e80471c5c6c | 1079 | float xSonarLeft=poseKplus1K.data[0][0]+this->sonarLeft.distanceX*cos(poseKplus1K.data[0][2])-this->sonarLeft.distanceY*sin(poseKplus1K.data[0][2]); |
Ludwigfr | 12:1e80471c5c6c | 1080 | float ySonarLeft=poseKplus1K.data[1][0]+this->sonarLeft.distanceX*sin(poseKplus1K.data[0][2])-this->sonarLeft.distanceY*cos(poseKplus1K.data[0][2]); |
Ludwigfr | 12:1e80471c5c6c | 1081 | float angleSonarLeft=poseKplus1K.data[0][2]+this->sonarLeft.angleFromCenter; |
Ludwigfr | 13:b0ddd71e8f08 | 1082 | if(angleSonarLeft > PI) |
Ludwigfr | 13:b0ddd71e8f08 | 1083 | angleSonarLeft=angleSonarLeft-2*PI; |
Ludwigfr | 13:b0ddd71e8f08 | 1084 | if(angleSonarLeft < -PI) |
Ludwigfr | 13:b0ddd71e8f08 | 1085 | angleSonarLeft=angleSonarLeft+2*PI; |
Ludwigfr | 12:1e80471c5c6c | 1086 | |
Ludwigfr | 12:1e80471c5c6c | 1087 | float xSonarFront=poseKplus1K.data[0][0]+this->sonarFront.distanceX*cos(poseKplus1K.data[0][2])-this->sonarFront.distanceY*sin(poseKplus1K.data[0][2]); |
Ludwigfr | 12:1e80471c5c6c | 1088 | float ySonarFront=poseKplus1K.data[1][0]+this->sonarFront.distanceX*sin(poseKplus1K.data[0][2])-this->sonarFront.distanceY*cos(poseKplus1K.data[0][2]); |
Ludwigfr | 12:1e80471c5c6c | 1089 | float angleSonarFront=poseKplus1K.data[0][2]+this->sonarFront.angleFromCenter; |
Ludwigfr | 13:b0ddd71e8f08 | 1090 | if(angleSonarFront > PI) |
Ludwigfr | 13:b0ddd71e8f08 | 1091 | angleSonarFront=angleSonarFront-2*PI; |
Ludwigfr | 13:b0ddd71e8f08 | 1092 | if(angleSonarFront < -PI) |
Ludwigfr | 13:b0ddd71e8f08 | 1093 | angleSonarFront=angleSonarFront+2*PI; |
Ludwigfr | 12:1e80471c5c6c | 1094 | |
Ludwigfr | 12:1e80471c5c6c | 1095 | float xSonarRight=poseKplus1K.data[0][0]+this->sonarRight.distanceX*cos(poseKplus1K.data[0][2])-this->sonarRight.distanceY*sin(poseKplus1K.data[0][2]); |
Ludwigfr | 12:1e80471c5c6c | 1096 | float ySonarRight=poseKplus1K.data[1][0]+this->sonarRight.distanceX*sin(poseKplus1K.data[0][2])-this->sonarRight.distanceY*cos(poseKplus1K.data[0][2]); |
Ludwigfr | 12:1e80471c5c6c | 1097 | float angleSonarRight=poseKplus1K.data[0][2]+this->sonarRight.angleFromCenter; |
Ludwigfr | 13:b0ddd71e8f08 | 1098 | if(angleSonarRight > PI) |
Ludwigfr | 13:b0ddd71e8f08 | 1099 | angleSonarRight=angleSonarRight-2*PI; |
Ludwigfr | 13:b0ddd71e8f08 | 1100 | if(angleSonarRight < -PI) |
Ludwigfr | 13:b0ddd71e8f08 | 1101 | angleSonarRight=angleSonarRight+2*PI; |
Ludwigfr | 12:1e80471c5c6c | 1102 | |
Ludwigfr | 12:1e80471c5c6c | 1103 | //note: last line divided by d, [0][2] all angles are theta^ teacher's advice, error in paper |
Ludwigfr | 12:1e80471c5c6c | 1104 | //left |
Ludwigfr | 12:1e80471c5c6c | 1105 | jacobianOfObservationLeft.data[0][0]=(xSonarLeft-xClosestCellLeft)/leftCmEstimated; |
Ludwigfr | 12:1e80471c5c6c | 1106 | jacobianOfObservationLeft.data[0][1]=(ySonarLeft-yClosestCellLeft)/leftCmEstimated; |
Ludwigfr | 12:1e80471c5c6c | 1107 | jacobianOfObservationLeft.data[0][2]=(1/leftCmEstimated)*(xClosestCellLeft-xSonarLeft)*(this->sonarLeft.distanceX*sin(angleSonarLeft)+this->sonarLeft.distanceY*cos(angleSonarLeft))+(yClosestCellLeft-ySonarLeft)*(-this->sonarLeft.distanceX*cos(angleSonarLeft)+this->sonarLeft.distanceY*sin(angleSonarLeft)); |
Ludwigfr | 12:1e80471c5c6c | 1108 | |
Ludwigfr | 12:1e80471c5c6c | 1109 | //front |
Ludwigfr | 12:1e80471c5c6c | 1110 | jacobianOfObservationFront.data[0][0]=(xSonarFront-xClosestCellFront)/frontCmEstimated; |
Ludwigfr | 12:1e80471c5c6c | 1111 | jacobianOfObservationFront.data[0][1]=(ySonarFront-yClosestCellFront)/frontCmEstimated; |
Ludwigfr | 12:1e80471c5c6c | 1112 | jacobianOfObservationFront.data[0][2]=(1/frontCmEstimated)*(xClosestCellFront-xSonarFront)*(this->sonarFront.distanceX*sin(angleSonarFront)+this->sonarFront.distanceY*cos(angleSonarFront))+(yClosestCellFront-ySonarFront)*(-this->sonarFront.distanceX*cos(angleSonarFront)+this->sonarFront.distanceY*sin(angleSonarFront)); |
Ludwigfr | 12:1e80471c5c6c | 1113 | |
Ludwigfr | 12:1e80471c5c6c | 1114 | //right |
Ludwigfr | 12:1e80471c5c6c | 1115 | jacobianOfObservationRight.data[0][0]=(xSonarRight-xClosestCellRight)/rightCmEstimated; |
Ludwigfr | 12:1e80471c5c6c | 1116 | jacobianOfObservationRight.data[0][1]=(ySonarRight-yClosestCellRight)/rightCmEstimated; |
Ludwigfr | 12:1e80471c5c6c | 1117 | jacobianOfObservationRight.data[0][2]=(xClosestCellRight-xSonarRight)*(xSonarRight*sin(poseKplus1K.data[2][0])+ySonarRight*cos(poseKplus1K.data[2][0]))+(yClosestCellRight-ySonarRight)*(-xSonarRight*cos(poseKplus1K.data[2][0])+ySonarRight*sin(poseKplus1K.data[2][0])); |
Ludwigfr | 12:1e80471c5c6c | 1118 | jacobianOfObservationRight.data[0][2]=(1/rightCmEstimated)*(xClosestCellRight-xSonarRight)*(this->sonarRight.distanceX*sin(angleSonarRight)+this->sonarRight.distanceY*cos(angleSonarRight))+(yClosestCellRight-ySonarRight)*(-this->sonarRight.distanceX*cos(angleSonarRight)+this->sonarRight.distanceY*sin(angleSonarRight)); |
Ludwigfr | 9:1cc27f33d3e1 | 1119 | |
Ludwigfr | 12:1e80471c5c6c | 1120 | myMatrix jacobianOfObservationRightTranspose(3,1); |
Ludwigfr | 12:1e80471c5c6c | 1121 | jacobianOfObservationRightTranspose.fillWithTranspose(jacobianOfObservationRight); |
Ludwigfr | 12:1e80471c5c6c | 1122 | |
Ludwigfr | 12:1e80471c5c6c | 1123 | myMatrix jacobianOfObservationFrontTranspose(3,1); |
Ludwigfr | 12:1e80471c5c6c | 1124 | jacobianOfObservationFrontTranspose.fillWithTranspose(jacobianOfObservationFront); |
Ludwigfr | 12:1e80471c5c6c | 1125 | |
Ludwigfr | 12:1e80471c5c6c | 1126 | myMatrix jacobianOfObservationLeftTranspose(3,1); |
Ludwigfr | 12:1e80471c5c6c | 1127 | jacobianOfObservationLeftTranspose.fillWithTranspose(jacobianOfObservationLeft); |
Ludwigfr | 13:b0ddd71e8f08 | 1128 | //error constants 0,0,0 sonars perfect; must be found by experimenting; gives mean and standart deviation |
Ludwigfr | 12:1e80471c5c6c | 1129 | //in centimeters |
Ludwigfr | 12:1e80471c5c6c | 1130 | float R_front=4; |
Ludwigfr | 12:1e80471c5c6c | 1131 | float R_left=4; |
Ludwigfr | 12:1e80471c5c6c | 1132 | float R_right=4; |
Ludwigfr | 12:1e80471c5c6c | 1133 | |
Ludwigfr | 12:1e80471c5c6c | 1134 | //R-> 4 in diagonal |
Ludwigfr | 12:1e80471c5c6c | 1135 | |
Ludwigfr | 13:b0ddd71e8f08 | 1136 | //for each sonar (concatenated covariance matrix of innovation) |
Ludwigfr | 12:1e80471c5c6c | 1137 | //equ (12), innovationCovariance =JacobianObservation*covariancePositionEstimationKplus1K*JacobianObservationTranspose+R |
Ludwigfr | 12:1e80471c5c6c | 1138 | myMatrix temp4(1,3); |
Ludwigfr | 12:1e80471c5c6c | 1139 | temp4.fillByMultiplication(jacobianOfObservationFront,covariancePositionEstimationKplus1K); |
Ludwigfr | 12:1e80471c5c6c | 1140 | myMatrix temp5(1,1); |
Ludwigfr | 12:1e80471c5c6c | 1141 | temp5.fillByMultiplication(temp4,jacobianOfObservationFrontTranspose); |
Ludwigfr | 12:1e80471c5c6c | 1142 | float innovationCovarianceFront=temp5.data[0][0]+R_front; |
Ludwigfr | 12:1e80471c5c6c | 1143 | temp4.fillWithZeroes(); |
Ludwigfr | 12:1e80471c5c6c | 1144 | temp5.fillWithZeroes(); |
Ludwigfr | 12:1e80471c5c6c | 1145 | |
Ludwigfr | 12:1e80471c5c6c | 1146 | temp4.fillByMultiplication(jacobianOfObservationLeft,covariancePositionEstimationKplus1K); |
Ludwigfr | 12:1e80471c5c6c | 1147 | temp5.fillByMultiplication(temp4,jacobianOfObservationLeftTranspose); |
Ludwigfr | 12:1e80471c5c6c | 1148 | float innovationCovarianceLeft=temp5.data[0][0]+R_left; |
Ludwigfr | 12:1e80471c5c6c | 1149 | temp4.fillWithZeroes(); |
Ludwigfr | 12:1e80471c5c6c | 1150 | temp5.fillWithZeroes(); |
Ludwigfr | 12:1e80471c5c6c | 1151 | |
Ludwigfr | 12:1e80471c5c6c | 1152 | temp4.fillByMultiplication(jacobianOfObservationRight,covariancePositionEstimationKplus1K); |
Ludwigfr | 12:1e80471c5c6c | 1153 | temp5.fillByMultiplication(temp4,jacobianOfObservationRightTranspose); |
Ludwigfr | 12:1e80471c5c6c | 1154 | float innovationCovarianceRight=temp5.data[0][0]+R_right; |
Ludwigfr | 12:1e80471c5c6c | 1155 | |
Ludwigfr | 12:1e80471c5c6c | 1156 | this->printMatrix(jacobianOfObservationLeft); |
Ludwigfr | 12:1e80471c5c6c | 1157 | this->printMatrix(jacobianOfObservationFront); |
Ludwigfr | 12:1e80471c5c6c | 1158 | this->printMatrix(jacobianOfObservationRight); |
Ludwigfr | 12:1e80471c5c6c | 1159 | pc.printf("\r\ninnovationCovariance L:%f, F:%f, R:%f",innovationCovarianceLeft,innovationCovarianceFront,innovationCovarianceRight); |
Ludwigfr | 12:1e80471c5c6c | 1160 | |
Ludwigfr | 12:1e80471c5c6c | 1161 | //get the innoncation: the value of the difference between the actual measure and what we anticipated |
Ludwigfr | 12:1e80471c5c6c | 1162 | float innovationLeft=leftCm-leftCmEstimated; |
Ludwigfr | 12:1e80471c5c6c | 1163 | float innovationFront=frontCm-frontCmEstimated; |
Ludwigfr | 12:1e80471c5c6c | 1164 | float innovationRight=rightCm-rightCmEstimated; |
Ludwigfr | 12:1e80471c5c6c | 1165 | |
Ludwigfr | 12:1e80471c5c6c | 1166 | //check if it pass the validation gate |
Ludwigfr | 12:1e80471c5c6c | 1167 | float gateScoreLeft=innovationLeft*innovationLeft/innovationCovarianceLeft; |
Ludwigfr | 12:1e80471c5c6c | 1168 | float gateScoreFront=innovationFront*innovationFront/innovationCovarianceFront; |
Ludwigfr | 12:1e80471c5c6c | 1169 | float gateScoreRight=innovationRight*innovationRight/innovationCovarianceRight; |
Ludwigfr | 12:1e80471c5c6c | 1170 | |
Ludwigfr | 12:1e80471c5c6c | 1171 | //5cm -> 25 |
Ludwigfr | 12:1e80471c5c6c | 1172 | int errorsquare=25;//constant error |
Ludwigfr | 12:1e80471c5c6c | 1173 | |
Ludwigfr | 12:1e80471c5c6c | 1174 | int nbPassed=0; |
Ludwigfr | 12:1e80471c5c6c | 1175 | |
Ludwigfr | 12:1e80471c5c6c | 1176 | if(gateScoreLeft <= errorsquare) |
Ludwigfr | 12:1e80471c5c6c | 1177 | nbPassed+=1; |
Ludwigfr | 12:1e80471c5c6c | 1178 | if(gateScoreFront <= errorsquare) |
Ludwigfr | 12:1e80471c5c6c | 1179 | nbPassed+=10; |
Ludwigfr | 12:1e80471c5c6c | 1180 | if(gateScoreRight <= errorsquare) |
Ludwigfr | 12:1e80471c5c6c | 1181 | nbPassed+=100; |
Ludwigfr | 12:1e80471c5c6c | 1182 | //for those who passed |
Ludwigfr | 12:1e80471c5c6c | 1183 | //compute composite innovation |
Ludwigfr | 12:1e80471c5c6c | 1184 | |
Ludwigfr | 12:1e80471c5c6c | 1185 | pc.printf("\r\nscore L:%f, F:%f, R:%f",gateScoreLeft,gateScoreFront,gateScoreRight); |
Ludwigfr | 12:1e80471c5c6c | 1186 | pc.printf("\r\nnbPassed=%d",nbPassed); |
Ludwigfr | 9:1cc27f33d3e1 | 1187 | |
Ludwigfr | 12:1e80471c5c6c | 1188 | //compositeMeasurementJacobian |
Ludwigfr | 12:1e80471c5c6c | 1189 | myMatrix compositeMeasurementJacobian3x3(3,3); |
Ludwigfr | 12:1e80471c5c6c | 1190 | myMatrix compositeMeasurementJacobian2x3(2,3); |
Ludwigfr | 12:1e80471c5c6c | 1191 | myMatrix compositeMeasurementJacobian1x3(1,3); |
Ludwigfr | 12:1e80471c5c6c | 1192 | |
Ludwigfr | 12:1e80471c5c6c | 1193 | myMatrix compositeMeasurementJacobian3x3Transpose(3,3); |
Ludwigfr | 12:1e80471c5c6c | 1194 | myMatrix compositeMeasurementJacobian2x3Transpose(3,2); |
Ludwigfr | 12:1e80471c5c6c | 1195 | myMatrix compositeMeasurementJacobian1x3Transpose(3,1); |
Ludwigfr | 9:1cc27f33d3e1 | 1196 | |
Ludwigfr | 12:1e80471c5c6c | 1197 | //compositeInnovation |
Ludwigfr | 12:1e80471c5c6c | 1198 | myMatrix compositeInnovation3x1(3,1); |
Ludwigfr | 12:1e80471c5c6c | 1199 | myMatrix compositeInnovation2x1(2,1); |
Ludwigfr | 12:1e80471c5c6c | 1200 | myMatrix compositeInnovation1x1(1,1); |
Ludwigfr | 12:1e80471c5c6c | 1201 | |
Ludwigfr | 12:1e80471c5c6c | 1202 | //compositeInnovationCovariance |
Ludwigfr | 12:1e80471c5c6c | 1203 | myMatrix compositeInnovationCovariance3x3(3,3); |
Ludwigfr | 12:1e80471c5c6c | 1204 | myMatrix compositeInnovationCovariance2x2(2,2); |
Ludwigfr | 12:1e80471c5c6c | 1205 | myMatrix compositeInnovationCovariance1x1(1,1); |
Ludwigfr | 12:1e80471c5c6c | 1206 | |
Ludwigfr | 12:1e80471c5c6c | 1207 | myMatrix tempCompositeInnovationCovariance3x3(3,3); |
Ludwigfr | 12:1e80471c5c6c | 1208 | myMatrix tempCompositeInnovationCovariance2x2(2,2); |
Ludwigfr | 12:1e80471c5c6c | 1209 | |
Ludwigfr | 12:1e80471c5c6c | 1210 | myMatrix compositeInnovationCovariance3x3Inverse(3,3); |
Ludwigfr | 12:1e80471c5c6c | 1211 | myMatrix compositeInnovationCovariance2x2Inverse(2,2); |
Ludwigfr | 12:1e80471c5c6c | 1212 | myMatrix compositeInnovationCovariance1x1Inverse(1,1); |
Ludwigfr | 12:1e80471c5c6c | 1213 | |
Ludwigfr | 12:1e80471c5c6c | 1214 | //Kalman Gain |
Ludwigfr | 12:1e80471c5c6c | 1215 | myMatrix kalmanGain3X3(3,3); |
Ludwigfr | 12:1e80471c5c6c | 1216 | myMatrix kalmanGain3X2(3,2); |
Ludwigfr | 12:1e80471c5c6c | 1217 | myMatrix kalmanGain3X1(3,1); |
Ludwigfr | 12:1e80471c5c6c | 1218 | |
Ludwigfr | 12:1e80471c5c6c | 1219 | myMatrix tempKalmanGain3X3(3,3); |
Ludwigfr | 12:1e80471c5c6c | 1220 | myMatrix tempKalmanGain3X2(3,2); |
Ludwigfr | 12:1e80471c5c6c | 1221 | myMatrix tempKalmanGain3X1(3,1); |
Ludwigfr | 12:1e80471c5c6c | 1222 | |
Ludwigfr | 12:1e80471c5c6c | 1223 | myMatrix kalmanGain3X3Transpose(3,3); |
Ludwigfr | 12:1e80471c5c6c | 1224 | myMatrix kalmanGain3X2Transpose(2,3); |
Ludwigfr | 12:1e80471c5c6c | 1225 | myMatrix kalmanGain3X1Transpose(1,3); |
Ludwigfr | 12:1e80471c5c6c | 1226 | |
Ludwigfr | 12:1e80471c5c6c | 1227 | //new pose estimation |
Ludwigfr | 12:1e80471c5c6c | 1228 | myMatrix poseKplus1Kplus1(3,1); |
Ludwigfr | 12:1e80471c5c6c | 1229 | poseKplus1Kplus1.fillByCopy(poseKplus1K); |
Ludwigfr | 12:1e80471c5c6c | 1230 | myMatrix tempPoseKplus1Kplus1(3,1); |
Ludwigfr | 12:1e80471c5c6c | 1231 | |
Ludwigfr | 12:1e80471c5c6c | 1232 | //covariancePositionEstimationKplus1Kplus1 |
Ludwigfr | 12:1e80471c5c6c | 1233 | myMatrix covariancePositionEstimationKplus1Kplus1(3,3); |
Ludwigfr | 12:1e80471c5c6c | 1234 | covariancePositionEstimationKplus1Kplus1.fillByCopy(covariancePositionEstimationKplus1K); |
Ludwigfr | 12:1e80471c5c6c | 1235 | |
Ludwigfr | 12:1e80471c5c6c | 1236 | myMatrix temp2CovariancePositionEstimationKplus1Kplus13x3(3,3); |
Ludwigfr | 12:1e80471c5c6c | 1237 | myMatrix tempCovariancePositionEstimationKplus1Kplus13x3(3,3); |
Ludwigfr | 12:1e80471c5c6c | 1238 | myMatrix tempCovariancePositionEstimationKplus1Kplus13x2(3,2); |
Ludwigfr | 12:1e80471c5c6c | 1239 | myMatrix tempCovariancePositionEstimationKplus1Kplus13x1(3,1); |
Ludwigfr | 12:1e80471c5c6c | 1240 | |
Ludwigfr | 12:1e80471c5c6c | 1241 | //we do not use the composite measurement jacobian (16), we directly use the values from the measurement jacobian (jacobianOfObservation) |
Ludwigfr | 12:1e80471c5c6c | 1242 | switch(nbPassed){ |
Ludwigfr | 12:1e80471c5c6c | 1243 | case 0://none |
Ludwigfr | 12:1e80471c5c6c | 1244 | //nothings happens it's okay |
Ludwigfr | 12:1e80471c5c6c | 1245 | pc.printf("\r\n000"); |
Ludwigfr | 12:1e80471c5c6c | 1246 | break; |
Ludwigfr | 12:1e80471c5c6c | 1247 | case 1://left |
Ludwigfr | 12:1e80471c5c6c | 1248 | //compute compositeMeasurementJacobian |
Ludwigfr | 12:1e80471c5c6c | 1249 | //here compositeMeasurementJacobian= jacobianOfObservationLeft |
Ludwigfr | 12:1e80471c5c6c | 1250 | compositeMeasurementJacobian1x3.fillByCopy(jacobianOfObservationLeft); |
Ludwigfr | 12:1e80471c5c6c | 1251 | pc.printf("\r\n1:calcul compositeMeasurementJacobian1x3 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1252 | //get the compositeMeasurementJacobianTranspose |
Ludwigfr | 12:1e80471c5c6c | 1253 | compositeMeasurementJacobian1x3Transpose.fillWithTranspose(compositeMeasurementJacobian1x3); |
Ludwigfr | 12:1e80471c5c6c | 1254 | //compute compositeInnovation |
Ludwigfr | 12:1e80471c5c6c | 1255 | //here compositeInnovation=innovationLeft |
Ludwigfr | 12:1e80471c5c6c | 1256 | compositeInnovation1x1.data[0][0]=innovationLeft; |
Ludwigfr | 12:1e80471c5c6c | 1257 | pc.printf("\r\n1:calcul compositeInnovation1x1 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1258 | //compute compositeInnovationCovariance=compositeMeasurementJacobian*covariancePositionEstimationKplus1K*compositeMeasurementJacobianTranpose |
Ludwigfr | 12:1e80471c5c6c | 1259 | //add the right R on the diagonal |
Ludwigfr | 12:1e80471c5c6c | 1260 | //here compositeInnovationCovariance=innovationCovarianceLeft |
Ludwigfr | 12:1e80471c5c6c | 1261 | compositeInnovationCovariance1x1.data[0][0]=innovationCovarianceLeft; |
Ludwigfr | 12:1e80471c5c6c | 1262 | pc.printf("\r\n1:calcul compositeInnovationCovariance1x1 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1263 | //get the inverse of the compositeInnovationCovariance |
Ludwigfr | 12:1e80471c5c6c | 1264 | compositeInnovationCovariance1x1Inverse.data[0][0]=1/innovationCovarianceLeft; |
Ludwigfr | 12:1e80471c5c6c | 1265 | pc.printf("\r\n1:calcul compositeInnovationCovariance1x1Inverse passed"); |
Ludwigfr | 12:1e80471c5c6c | 1266 | //compute KalmanGain=covariancePositionEstimationKplus1K*compositeMeasurementJacobianTranspose*Inverse(compositeInnovationCovariance) |
Ludwigfr | 12:1e80471c5c6c | 1267 | tempKalmanGain3X1.fillByMultiplication(covariancePositionEstimationKplus1K,compositeMeasurementJacobian1x3Transpose); |
Ludwigfr | 12:1e80471c5c6c | 1268 | kalmanGain3X1.fillByMultiplication(tempKalmanGain3X1,compositeInnovationCovariance1x1Inverse); |
Ludwigfr | 12:1e80471c5c6c | 1269 | pc.printf("\r\n1:calcul kalmanGain3X1 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1270 | //get the transpose of the kalman gain |
Ludwigfr | 12:1e80471c5c6c | 1271 | kalmanGain3X1Transpose.fillWithTranspose(kalmanGain3X1); |
Ludwigfr | 12:1e80471c5c6c | 1272 | //update pose estimation=old pose estimation + kalman gain*compositeInnovation |
Ludwigfr | 12:1e80471c5c6c | 1273 | tempPoseKplus1Kplus1.fillByMultiplication(kalmanGain3X1,compositeInnovation1x1); |
Ludwigfr | 12:1e80471c5c6c | 1274 | poseKplus1Kplus1.addition(tempPoseKplus1Kplus1); |
Ludwigfr | 12:1e80471c5c6c | 1275 | pc.printf("\r\n1:calcul poseKplus1Kplus1 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1276 | //compute covariancePositionEstimationKplus1Kplus1=covariancePositionEstimationKplus1K-kalmanGain*compositeInnovationCovariance*KalmanGainTranspose |
Ludwigfr | 12:1e80471c5c6c | 1277 | tempCovariancePositionEstimationKplus1Kplus13x1.fillByMultiplication(kalmanGain3X1,compositeInnovationCovariance1x1); |
Ludwigfr | 12:1e80471c5c6c | 1278 | tempCovariancePositionEstimationKplus1Kplus13x3.fillByMultiplication(tempCovariancePositionEstimationKplus1Kplus13x1,kalmanGain3X1Transpose); |
Ludwigfr | 12:1e80471c5c6c | 1279 | covariancePositionEstimationKplus1Kplus1.subtraction(tempCovariancePositionEstimationKplus1Kplus13x3); |
Ludwigfr | 12:1e80471c5c6c | 1280 | pc.printf("\r\n1:calcul covariancePositionEstimationKplus1Kplus1 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1281 | break; |
Ludwigfr | 12:1e80471c5c6c | 1282 | case 10://front |
Ludwigfr | 12:1e80471c5c6c | 1283 | //compute compositeMeasurementJacobian |
Ludwigfr | 12:1e80471c5c6c | 1284 | compositeMeasurementJacobian1x3.fillByCopy(jacobianOfObservationFront); |
Ludwigfr | 12:1e80471c5c6c | 1285 | pc.printf("\r\n10:calcul compositeMeasurementJacobian1x3 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1286 | //get the compositeMeasurementJacobianTranspose |
Ludwigfr | 12:1e80471c5c6c | 1287 | compositeMeasurementJacobian1x3Transpose.fillWithTranspose(compositeMeasurementJacobian1x3); |
Ludwigfr | 12:1e80471c5c6c | 1288 | //compute compositeInnovation |
Ludwigfr | 12:1e80471c5c6c | 1289 | compositeInnovation1x1.data[0][0]=innovationFront; |
Ludwigfr | 12:1e80471c5c6c | 1290 | pc.printf("\r\n10:calcul compositeInnovation1x1 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1291 | //compute compositeInnovationCovariance=compositeMeasurementJacobian*covariancePositionEstimationKplus1K*compositeMeasurementJacobianTranpose |
Ludwigfr | 12:1e80471c5c6c | 1292 | //add the right R on the diagonal |
Ludwigfr | 12:1e80471c5c6c | 1293 | compositeInnovationCovariance1x1.data[0][0]=innovationCovarianceFront; |
Ludwigfr | 12:1e80471c5c6c | 1294 | pc.printf("\r\n10:calcul compositeInnovationCovariance1x1 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1295 | //get the inverse of the compositeInnovationCovariance |
Ludwigfr | 12:1e80471c5c6c | 1296 | compositeInnovationCovariance1x1Inverse.data[0][0]=1/innovationCovarianceFront; |
Ludwigfr | 12:1e80471c5c6c | 1297 | pc.printf("\r\n10:calcul compositeInnovationCovariance1x1Inverse passed"); |
Ludwigfr | 12:1e80471c5c6c | 1298 | //compute KalmanGain=covariancePositionEstimationKplus1K*compositeMeasurementJacobianTranspose*Inverse(compositeInnovationCovariance) |
Ludwigfr | 12:1e80471c5c6c | 1299 | tempKalmanGain3X1.fillByMultiplication(covariancePositionEstimationKplus1K,compositeMeasurementJacobian1x3Transpose); |
Ludwigfr | 12:1e80471c5c6c | 1300 | kalmanGain3X1.fillByMultiplication(tempKalmanGain3X1,compositeInnovationCovariance1x1Inverse); |
Ludwigfr | 12:1e80471c5c6c | 1301 | pc.printf("\r\n10:calcul kalmanGain3X1 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1302 | //get the transpose of the kalman gain |
Ludwigfr | 12:1e80471c5c6c | 1303 | kalmanGain3X1Transpose.fillWithTranspose(kalmanGain3X1); |
Ludwigfr | 12:1e80471c5c6c | 1304 | //update pose estimation=old pose estimation + kalman gain*compositeInnovation |
Ludwigfr | 12:1e80471c5c6c | 1305 | tempPoseKplus1Kplus1.fillByMultiplication(kalmanGain3X1,compositeInnovation1x1); |
Ludwigfr | 12:1e80471c5c6c | 1306 | poseKplus1Kplus1.addition(tempPoseKplus1Kplus1); |
Ludwigfr | 12:1e80471c5c6c | 1307 | pc.printf("\r\n10:calcul poseKplus1Kplus1 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1308 | //compute covariancePositionEstimationKplus1Kplus1=covariancePositionEstimationKplus1K-kalmanGain*compositeInnovationCovariance*KalmanGainTranspose |
Ludwigfr | 12:1e80471c5c6c | 1309 | tempCovariancePositionEstimationKplus1Kplus13x1.fillByMultiplication(kalmanGain3X1,compositeInnovationCovariance1x1); |
Ludwigfr | 12:1e80471c5c6c | 1310 | tempCovariancePositionEstimationKplus1Kplus13x3.fillByMultiplication(tempCovariancePositionEstimationKplus1Kplus13x1,kalmanGain3X1Transpose); |
Ludwigfr | 12:1e80471c5c6c | 1311 | covariancePositionEstimationKplus1Kplus1.subtraction(tempCovariancePositionEstimationKplus1Kplus13x3); |
Ludwigfr | 12:1e80471c5c6c | 1312 | pc.printf("\r\n10:calcul covariancePositionEstimationKplus1Kplus1 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1313 | break; |
Ludwigfr | 12:1e80471c5c6c | 1314 | case 11://left and front |
Ludwigfr | 12:1e80471c5c6c | 1315 | //compute compositeMeasurementJacobian |
Ludwigfr | 12:1e80471c5c6c | 1316 | compositeMeasurementJacobian2x3.data[0][0]=jacobianOfObservationLeft.data[0][0]; |
Ludwigfr | 12:1e80471c5c6c | 1317 | compositeMeasurementJacobian2x3.data[0][1]=jacobianOfObservationLeft.data[0][1]; |
Ludwigfr | 12:1e80471c5c6c | 1318 | compositeMeasurementJacobian2x3.data[0][2]=jacobianOfObservationLeft.data[0][2]; |
Ludwigfr | 12:1e80471c5c6c | 1319 | |
Ludwigfr | 12:1e80471c5c6c | 1320 | compositeMeasurementJacobian2x3.data[1][0]=jacobianOfObservationFront.data[0][0]; |
Ludwigfr | 12:1e80471c5c6c | 1321 | compositeMeasurementJacobian2x3.data[1][1]=jacobianOfObservationFront.data[0][1]; |
Ludwigfr | 12:1e80471c5c6c | 1322 | compositeMeasurementJacobian2x3.data[1][2]=jacobianOfObservationFront.data[0][2]; |
Ludwigfr | 12:1e80471c5c6c | 1323 | pc.printf("\r\n11:calcul compositeMeasurementJacobian2x3 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1324 | //get the compositeMeasurementJacobianTranspose |
Ludwigfr | 12:1e80471c5c6c | 1325 | compositeMeasurementJacobian2x3Transpose.fillWithTranspose(compositeMeasurementJacobian2x3); |
Ludwigfr | 12:1e80471c5c6c | 1326 | //compute compositeInnovation |
Ludwigfr | 12:1e80471c5c6c | 1327 | compositeInnovation2x1.data[0][0]=innovationLeft; |
Ludwigfr | 12:1e80471c5c6c | 1328 | compositeInnovation2x1.data[1][0]=innovationFront; |
Ludwigfr | 12:1e80471c5c6c | 1329 | pc.printf("\r\n11:calcul compositeInnovation2x1 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1330 | //compute compositeInnovationCovariance=compositeMeasurementJacobian*covariancePositionEstimationKplus1K*compositeMeasurementJacobianTranpose+R |
Ludwigfr | 12:1e80471c5c6c | 1331 | tempCompositeInnovationCovariance2x2.fillByMultiplication(compositeMeasurementJacobian2x3,covariancePositionEstimationKplus1K); |
Ludwigfr | 12:1e80471c5c6c | 1332 | compositeInnovationCovariance2x2.fillByMultiplication(tempCompositeInnovationCovariance2x2,compositeMeasurementJacobian2x3Transpose); |
Ludwigfr | 12:1e80471c5c6c | 1333 | //add the right R on the diagonal |
Ludwigfr | 12:1e80471c5c6c | 1334 | compositeInnovationCovariance2x2.data[0][0]+=R_left; |
Ludwigfr | 12:1e80471c5c6c | 1335 | compositeInnovationCovariance2x2.data[1][1]+=R_front; |
Ludwigfr | 12:1e80471c5c6c | 1336 | pc.printf("\r\n11:calcul compositeInnovationCovariance2x2 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1337 | //get the inverse of the compositeInnovationCovariance |
Ludwigfr | 12:1e80471c5c6c | 1338 | compositeInnovationCovariance2x2Inverse.fillWithInverse(compositeInnovationCovariance2x2); |
Ludwigfr | 12:1e80471c5c6c | 1339 | pc.printf("\r\n11:calcul compositeInnovationCovariance2x2Inverse passed"); |
Ludwigfr | 12:1e80471c5c6c | 1340 | //compute KalmanGain=covariancePositionEstimationKplus1K*compositeMeasurementJacobianTranspose*Inverse(compositeInnovationCovariance) |
Ludwigfr | 12:1e80471c5c6c | 1341 | tempKalmanGain3X2.fillByMultiplication(covariancePositionEstimationKplus1K,compositeMeasurementJacobian2x3Transpose); |
Ludwigfr | 12:1e80471c5c6c | 1342 | kalmanGain3X2.fillByMultiplication(tempKalmanGain3X2,compositeInnovationCovariance2x2Inverse); |
Ludwigfr | 12:1e80471c5c6c | 1343 | pc.printf("\r\n11:calcul kalmanGain3X2 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1344 | //get the transpose of the kalman gain |
Ludwigfr | 12:1e80471c5c6c | 1345 | kalmanGain3X2Transpose.fillWithTranspose(kalmanGain3X2); |
Ludwigfr | 12:1e80471c5c6c | 1346 | //update pose estimation=old pose estimation + kalman gain*compositeInnovation |
Ludwigfr | 12:1e80471c5c6c | 1347 | tempPoseKplus1Kplus1.fillByMultiplication(kalmanGain3X2,compositeInnovation2x1); |
Ludwigfr | 12:1e80471c5c6c | 1348 | poseKplus1Kplus1.addition(tempPoseKplus1Kplus1); |
Ludwigfr | 12:1e80471c5c6c | 1349 | pc.printf("\r\n11:calcul poseKplus1Kplus1 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1350 | //compute covariancePositionEstimationKplus1Kplus1=covariancePositionEstimationKplus1K-kalmanGain*compositeInnovationCovariance*KalmanGainTranspose |
Ludwigfr | 12:1e80471c5c6c | 1351 | tempCovariancePositionEstimationKplus1Kplus13x2.fillByMultiplication(kalmanGain3X2,compositeInnovationCovariance2x2); |
Ludwigfr | 12:1e80471c5c6c | 1352 | tempCovariancePositionEstimationKplus1Kplus13x3.fillByMultiplication(tempCovariancePositionEstimationKplus1Kplus13x2,kalmanGain3X2Transpose); |
Ludwigfr | 12:1e80471c5c6c | 1353 | covariancePositionEstimationKplus1Kplus1.subtraction(tempCovariancePositionEstimationKplus1Kplus13x3); |
Ludwigfr | 12:1e80471c5c6c | 1354 | pc.printf("\r\n11:calcul covariancePositionEstimationKplus1Kplus1 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1355 | break; |
Ludwigfr | 12:1e80471c5c6c | 1356 | |
Ludwigfr | 12:1e80471c5c6c | 1357 | case 100://right |
Ludwigfr | 12:1e80471c5c6c | 1358 | //compute compositeMeasurementJacobian |
Ludwigfr | 12:1e80471c5c6c | 1359 | compositeMeasurementJacobian1x3.fillByCopy(jacobianOfObservationRight); |
Ludwigfr | 12:1e80471c5c6c | 1360 | pc.printf("\r\n100:calcul compositeMeasurementJacobian1x3 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1361 | //get the compositeMeasurementJacobianTranspose |
Ludwigfr | 12:1e80471c5c6c | 1362 | compositeMeasurementJacobian1x3Transpose.fillWithTranspose(compositeMeasurementJacobian1x3); |
Ludwigfr | 12:1e80471c5c6c | 1363 | //compute compositeInnovation |
Ludwigfr | 12:1e80471c5c6c | 1364 | compositeInnovation1x1.data[0][0]=innovationRight; |
Ludwigfr | 12:1e80471c5c6c | 1365 | //compute compositeInnovationCovariance=compositeMeasurementJacobian*covariancePositionEstimationKplus1K*compositeMeasurementJacobianTranpose |
Ludwigfr | 12:1e80471c5c6c | 1366 | //add the right R on the diagonal |
Ludwigfr | 12:1e80471c5c6c | 1367 | compositeInnovationCovariance1x1.data[0][0]=innovationCovarianceRight; |
Ludwigfr | 12:1e80471c5c6c | 1368 | //get the inverse of the compositeInnovationCovariance |
Ludwigfr | 12:1e80471c5c6c | 1369 | compositeInnovationCovariance1x1Inverse.data[0][0]=1/innovationCovarianceRight; |
Ludwigfr | 12:1e80471c5c6c | 1370 | pc.printf("\r\n100:calcul compositeInnovationCovariance1x1Inverse passed"); |
Ludwigfr | 12:1e80471c5c6c | 1371 | //compute KalmanGain=covariancePositionEstimationKplus1K*compositeMeasurementJacobianTranspose*Inverse(compositeInnovationCovariance) |
Ludwigfr | 12:1e80471c5c6c | 1372 | tempKalmanGain3X1.fillByMultiplication(covariancePositionEstimationKplus1K,compositeMeasurementJacobian1x3Transpose); |
Ludwigfr | 12:1e80471c5c6c | 1373 | kalmanGain3X1.fillByMultiplication(tempKalmanGain3X1,compositeInnovationCovariance1x1Inverse); |
Ludwigfr | 12:1e80471c5c6c | 1374 | pc.printf("\r\n100:calcul kalmanGain3X1 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1375 | //get the transpose of the kalman gain |
Ludwigfr | 12:1e80471c5c6c | 1376 | kalmanGain3X1Transpose.fillWithTranspose(kalmanGain3X1); |
Ludwigfr | 12:1e80471c5c6c | 1377 | //update pose estimation=old pose estimation + kalman gain*compositeInnovation |
Ludwigfr | 12:1e80471c5c6c | 1378 | tempPoseKplus1Kplus1.fillByMultiplication(kalmanGain3X1,compositeInnovation1x1); |
Ludwigfr | 12:1e80471c5c6c | 1379 | poseKplus1Kplus1.addition(tempPoseKplus1Kplus1); |
Ludwigfr | 12:1e80471c5c6c | 1380 | pc.printf("\r\n100:calcul poseKplus1Kplus1 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1381 | //compute covariancePositionEstimationKplus1Kplus1=covariancePositionEstimationKplus1K-kalmanGain*compositeInnovationCovariance*KalmanGainTranspose |
Ludwigfr | 12:1e80471c5c6c | 1382 | tempCovariancePositionEstimationKplus1Kplus13x1.fillByMultiplication(kalmanGain3X1,compositeInnovationCovariance1x1); |
Ludwigfr | 12:1e80471c5c6c | 1383 | tempCovariancePositionEstimationKplus1Kplus13x3.fillByMultiplication(tempCovariancePositionEstimationKplus1Kplus13x1,kalmanGain3X1Transpose); |
Ludwigfr | 12:1e80471c5c6c | 1384 | covariancePositionEstimationKplus1Kplus1.subtraction(tempCovariancePositionEstimationKplus1Kplus13x3); |
Ludwigfr | 12:1e80471c5c6c | 1385 | pc.printf("\r\n100:calcul covariancePositionEstimationKplus1Kplus1 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1386 | break; |
Ludwigfr | 12:1e80471c5c6c | 1387 | case 101://left and right |
Ludwigfr | 12:1e80471c5c6c | 1388 | //compute compositeMeasurementJacobian |
Ludwigfr | 12:1e80471c5c6c | 1389 | compositeMeasurementJacobian2x3.data[0][0]=jacobianOfObservationLeft.data[0][0]; |
Ludwigfr | 12:1e80471c5c6c | 1390 | compositeMeasurementJacobian2x3.data[0][1]=jacobianOfObservationLeft.data[0][1]; |
Ludwigfr | 12:1e80471c5c6c | 1391 | compositeMeasurementJacobian2x3.data[0][2]=jacobianOfObservationLeft.data[0][2]; |
Ludwigfr | 12:1e80471c5c6c | 1392 | |
Ludwigfr | 12:1e80471c5c6c | 1393 | compositeMeasurementJacobian2x3.data[1][0]=jacobianOfObservationRight.data[0][0]; |
Ludwigfr | 12:1e80471c5c6c | 1394 | compositeMeasurementJacobian2x3.data[1][1]=jacobianOfObservationRight.data[0][1]; |
Ludwigfr | 12:1e80471c5c6c | 1395 | compositeMeasurementJacobian2x3.data[1][2]=jacobianOfObservationRight.data[0][2]; |
Ludwigfr | 12:1e80471c5c6c | 1396 | pc.printf("\r\n101:calcul compositeMeasurementJacobian2x3 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1397 | //get the compositeMeasurementJacobianTranspose |
Ludwigfr | 12:1e80471c5c6c | 1398 | compositeMeasurementJacobian2x3Transpose.fillWithTranspose(compositeMeasurementJacobian2x3); |
Ludwigfr | 12:1e80471c5c6c | 1399 | //compute compositeInnovation |
Ludwigfr | 12:1e80471c5c6c | 1400 | compositeInnovation2x1.data[0][0]=innovationLeft; |
Ludwigfr | 12:1e80471c5c6c | 1401 | compositeInnovation2x1.data[1][0]=innovationRight; |
Ludwigfr | 12:1e80471c5c6c | 1402 | //compute compositeInnovationCovariance=compositeMeasurementJacobian*covariancePositionEstimationKplus1K*compositeMeasurementJacobianTranpose+R |
Ludwigfr | 12:1e80471c5c6c | 1403 | tempCompositeInnovationCovariance2x2.fillByMultiplication(compositeMeasurementJacobian2x3,covariancePositionEstimationKplus1K); |
Ludwigfr | 12:1e80471c5c6c | 1404 | compositeInnovationCovariance2x2.fillByMultiplication(tempCompositeInnovationCovariance2x2,compositeMeasurementJacobian2x3Transpose); |
Ludwigfr | 12:1e80471c5c6c | 1405 | //add the right R on the diagonal |
Ludwigfr | 12:1e80471c5c6c | 1406 | compositeInnovationCovariance2x2.data[0][0]+=R_left; |
Ludwigfr | 12:1e80471c5c6c | 1407 | compositeInnovationCovariance2x2.data[1][1]+=R_right; |
Ludwigfr | 12:1e80471c5c6c | 1408 | pc.printf("\r\n101:calcul compositeInnovationCovariance2x2 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1409 | //get the inverse of the compositeInnovationCovariance |
Ludwigfr | 12:1e80471c5c6c | 1410 | compositeInnovationCovariance2x2Inverse.fillWithInverse(compositeInnovationCovariance2x2); |
Ludwigfr | 12:1e80471c5c6c | 1411 | pc.printf("\r\n101:calcul compositeInnovationCovariance2x2Inverse passed"); |
Ludwigfr | 12:1e80471c5c6c | 1412 | //compute KalmanGain=covariancePositionEstimationKplus1K*compositeMeasurementJacobianTranspose*Inverse(compositeInnovationCovariance) |
Ludwigfr | 12:1e80471c5c6c | 1413 | tempKalmanGain3X2.fillByMultiplication(covariancePositionEstimationKplus1K,compositeMeasurementJacobian2x3Transpose); |
Ludwigfr | 12:1e80471c5c6c | 1414 | kalmanGain3X2.fillByMultiplication(tempKalmanGain3X2,compositeInnovationCovariance2x2Inverse); |
Ludwigfr | 12:1e80471c5c6c | 1415 | pc.printf("\r\n101:calcul kalmanGain3X2 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1416 | //get the transpose of the kalman gain |
Ludwigfr | 12:1e80471c5c6c | 1417 | kalmanGain3X2Transpose.fillWithTranspose(kalmanGain3X2); |
Ludwigfr | 12:1e80471c5c6c | 1418 | //update pose estimation=old pose estimation + kalman gain*compositeInnovation |
Ludwigfr | 12:1e80471c5c6c | 1419 | tempPoseKplus1Kplus1.fillByMultiplication(kalmanGain3X2,compositeInnovation2x1); |
Ludwigfr | 12:1e80471c5c6c | 1420 | poseKplus1Kplus1.addition(tempPoseKplus1Kplus1); |
Ludwigfr | 12:1e80471c5c6c | 1421 | pc.printf("\r\n101:calcul poseKplus1Kplus1 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1422 | //compute covariancePositionEstimationKplus1Kplus1=covariancePositionEstimationKplus1K-kalmanGain*compositeInnovationCovariance*KalmanGainTranspose |
Ludwigfr | 12:1e80471c5c6c | 1423 | tempCovariancePositionEstimationKplus1Kplus13x2.fillByMultiplication(kalmanGain3X2,compositeInnovationCovariance2x2); |
Ludwigfr | 12:1e80471c5c6c | 1424 | tempCovariancePositionEstimationKplus1Kplus13x3.fillByMultiplication(tempCovariancePositionEstimationKplus1Kplus13x2,kalmanGain3X2Transpose); |
Ludwigfr | 12:1e80471c5c6c | 1425 | covariancePositionEstimationKplus1Kplus1.subtraction(tempCovariancePositionEstimationKplus1Kplus13x3); |
Ludwigfr | 12:1e80471c5c6c | 1426 | pc.printf("\r\n101:calcul covariancePositionEstimationKplus1Kplus1 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1427 | break; |
Ludwigfr | 12:1e80471c5c6c | 1428 | case 110:// front and right |
Ludwigfr | 12:1e80471c5c6c | 1429 | //compute compositeMeasurementJacobian |
Ludwigfr | 12:1e80471c5c6c | 1430 | compositeMeasurementJacobian2x3.data[0][0]=jacobianOfObservationFront.data[0][0]; |
Ludwigfr | 12:1e80471c5c6c | 1431 | compositeMeasurementJacobian2x3.data[0][1]=jacobianOfObservationFront.data[0][1]; |
Ludwigfr | 12:1e80471c5c6c | 1432 | compositeMeasurementJacobian2x3.data[0][2]=jacobianOfObservationFront.data[0][2]; |
Ludwigfr | 12:1e80471c5c6c | 1433 | |
Ludwigfr | 12:1e80471c5c6c | 1434 | compositeMeasurementJacobian2x3.data[1][0]=jacobianOfObservationRight.data[0][0]; |
Ludwigfr | 12:1e80471c5c6c | 1435 | compositeMeasurementJacobian2x3.data[1][1]=jacobianOfObservationRight.data[0][1]; |
Ludwigfr | 12:1e80471c5c6c | 1436 | compositeMeasurementJacobian2x3.data[1][2]=jacobianOfObservationRight.data[0][2]; |
Ludwigfr | 12:1e80471c5c6c | 1437 | |
Ludwigfr | 12:1e80471c5c6c | 1438 | pc.printf("\r\n110:calcul compositeMeasurementJacobian2x3 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1439 | //get the compositeMeasurementJacobianTranspose |
Ludwigfr | 12:1e80471c5c6c | 1440 | compositeMeasurementJacobian2x3Transpose.fillWithTranspose(compositeMeasurementJacobian2x3); |
Ludwigfr | 12:1e80471c5c6c | 1441 | //compute compositeInnovation |
Ludwigfr | 12:1e80471c5c6c | 1442 | compositeInnovation2x1.data[0][0]=innovationFront; |
Ludwigfr | 12:1e80471c5c6c | 1443 | compositeInnovation2x1.data[1][0]=innovationRight; |
Ludwigfr | 12:1e80471c5c6c | 1444 | //compute compositeInnovationCovariance=compositeMeasurementJacobian*covariancePositionEstimationKplus1K*compositeMeasurementJacobianTranpose+R |
Ludwigfr | 12:1e80471c5c6c | 1445 | tempCompositeInnovationCovariance2x2.fillByMultiplication(compositeMeasurementJacobian2x3,covariancePositionEstimationKplus1K); |
Ludwigfr | 12:1e80471c5c6c | 1446 | compositeInnovationCovariance2x2.fillByMultiplication(tempCompositeInnovationCovariance2x2,compositeMeasurementJacobian2x3Transpose); |
Ludwigfr | 12:1e80471c5c6c | 1447 | //add the right R on the diagonal |
Ludwigfr | 12:1e80471c5c6c | 1448 | compositeInnovationCovariance2x2.data[0][0]+=R_front; |
Ludwigfr | 12:1e80471c5c6c | 1449 | compositeInnovationCovariance2x2.data[1][1]+=R_right; |
Ludwigfr | 12:1e80471c5c6c | 1450 | pc.printf("\r\n110:calcul compositeInnovationCovariance2x2 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1451 | //get the inverse of the compositeInnovationCovariance |
Ludwigfr | 12:1e80471c5c6c | 1452 | compositeInnovationCovariance2x2Inverse.fillWithInverse(compositeInnovationCovariance2x2); |
Ludwigfr | 12:1e80471c5c6c | 1453 | pc.printf("\r\n110:calcul compositeInnovationCovariance2x2Inverse passed"); |
Ludwigfr | 12:1e80471c5c6c | 1454 | //compute KalmanGain=covariancePositionEstimationKplus1K*compositeMeasurementJacobianTranspose*Inverse(compositeInnovationCovariance) |
Ludwigfr | 12:1e80471c5c6c | 1455 | tempKalmanGain3X2.fillByMultiplication(covariancePositionEstimationKplus1K,compositeMeasurementJacobian2x3Transpose); |
Ludwigfr | 12:1e80471c5c6c | 1456 | kalmanGain3X2.fillByMultiplication(tempKalmanGain3X2,compositeInnovationCovariance2x2Inverse); |
Ludwigfr | 12:1e80471c5c6c | 1457 | pc.printf("\r\n110:calcul kalmanGain3X2 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1458 | //get the transpose of the kalman gain |
Ludwigfr | 12:1e80471c5c6c | 1459 | kalmanGain3X2Transpose.fillWithTranspose(kalmanGain3X2); |
Ludwigfr | 12:1e80471c5c6c | 1460 | //update pose estimation=old pose estimation + kalman gain*compositeInnovation |
Ludwigfr | 12:1e80471c5c6c | 1461 | tempPoseKplus1Kplus1.fillByMultiplication(kalmanGain3X2,compositeInnovation2x1); |
Ludwigfr | 12:1e80471c5c6c | 1462 | poseKplus1Kplus1.addition(tempPoseKplus1Kplus1); |
Ludwigfr | 12:1e80471c5c6c | 1463 | pc.printf("\r\n110:calcul poseKplus1Kplus1 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1464 | //compute covariancePositionEstimationKplus1Kplus1=covariancePositionEstimationKplus1K-kalmanGain*compositeInnovationCovariance*KalmanGainTranspose |
Ludwigfr | 12:1e80471c5c6c | 1465 | tempCovariancePositionEstimationKplus1Kplus13x2.fillByMultiplication(kalmanGain3X2,compositeInnovationCovariance2x2); |
Ludwigfr | 12:1e80471c5c6c | 1466 | tempCovariancePositionEstimationKplus1Kplus13x3.fillByMultiplication(tempCovariancePositionEstimationKplus1Kplus13x2,kalmanGain3X2Transpose); |
Ludwigfr | 12:1e80471c5c6c | 1467 | covariancePositionEstimationKplus1Kplus1.subtraction(tempCovariancePositionEstimationKplus1Kplus13x3); |
Ludwigfr | 12:1e80471c5c6c | 1468 | pc.printf("\r\n110:calcul covariancePositionEstimationKplus1Kplus1 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1469 | break; |
Ludwigfr | 12:1e80471c5c6c | 1470 | case 111://left front and right |
Ludwigfr | 12:1e80471c5c6c | 1471 | //compute compositeMeasurementJacobian |
Ludwigfr | 12:1e80471c5c6c | 1472 | compositeMeasurementJacobian3x3.data[0][0]=jacobianOfObservationLeft.data[0][0]; |
Ludwigfr | 12:1e80471c5c6c | 1473 | compositeMeasurementJacobian3x3.data[0][1]=jacobianOfObservationLeft.data[0][1]; |
Ludwigfr | 12:1e80471c5c6c | 1474 | compositeMeasurementJacobian3x3.data[0][2]=jacobianOfObservationLeft.data[0][2]; |
Ludwigfr | 12:1e80471c5c6c | 1475 | |
Ludwigfr | 12:1e80471c5c6c | 1476 | compositeMeasurementJacobian3x3.data[1][0]=jacobianOfObservationFront.data[0][0]; |
Ludwigfr | 12:1e80471c5c6c | 1477 | compositeMeasurementJacobian3x3.data[1][1]=jacobianOfObservationFront.data[0][1]; |
Ludwigfr | 12:1e80471c5c6c | 1478 | compositeMeasurementJacobian3x3.data[1][2]=jacobianOfObservationFront.data[0][2]; |
Ludwigfr | 12:1e80471c5c6c | 1479 | |
Ludwigfr | 12:1e80471c5c6c | 1480 | compositeMeasurementJacobian3x3.data[2][0]=jacobianOfObservationRight.data[0][0]; |
Ludwigfr | 12:1e80471c5c6c | 1481 | compositeMeasurementJacobian3x3.data[2][1]=jacobianOfObservationRight.data[0][1]; |
Ludwigfr | 12:1e80471c5c6c | 1482 | compositeMeasurementJacobian3x3.data[2][2]=jacobianOfObservationRight.data[0][2]; |
Ludwigfr | 12:1e80471c5c6c | 1483 | |
Ludwigfr | 12:1e80471c5c6c | 1484 | pc.printf("\r\n111:calcul compositeMeasurementJacobian3x3 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1485 | //get the compositeMeasurementJacobianTranspose |
Ludwigfr | 12:1e80471c5c6c | 1486 | compositeMeasurementJacobian3x3Transpose.fillWithTranspose(compositeMeasurementJacobian3x3); |
Ludwigfr | 12:1e80471c5c6c | 1487 | //compute compositeInnovation |
Ludwigfr | 12:1e80471c5c6c | 1488 | compositeInnovation3x1.data[0][0]=innovationLeft; |
Ludwigfr | 12:1e80471c5c6c | 1489 | compositeInnovation3x1.data[1][0]=innovationFront; |
Ludwigfr | 12:1e80471c5c6c | 1490 | compositeInnovation3x1.data[2][0]=innovationRight; |
Ludwigfr | 12:1e80471c5c6c | 1491 | //compute compositeInnovationCovariance=compositeMeasurementJacobian*covariancePositionEstimationKplus1K*compositeMeasurementJacobianTranpose+R |
Ludwigfr | 12:1e80471c5c6c | 1492 | tempCompositeInnovationCovariance3x3.fillByMultiplication(compositeMeasurementJacobian3x3,covariancePositionEstimationKplus1K); |
Ludwigfr | 12:1e80471c5c6c | 1493 | compositeInnovationCovariance3x3.fillByMultiplication(tempCompositeInnovationCovariance3x3,compositeMeasurementJacobian3x3Transpose); |
Ludwigfr | 12:1e80471c5c6c | 1494 | //add the right R on the diagonal |
Ludwigfr | 12:1e80471c5c6c | 1495 | compositeInnovationCovariance3x3.data[0][0]+=R_left; |
Ludwigfr | 12:1e80471c5c6c | 1496 | compositeInnovationCovariance3x3.data[1][1]+=R_front; |
Ludwigfr | 12:1e80471c5c6c | 1497 | compositeInnovationCovariance3x3.data[2][2]+=R_right; |
Ludwigfr | 12:1e80471c5c6c | 1498 | pc.printf("\r\n111:calcul compositeInnovationCovariance3x3 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1499 | //get the inverse of the compositeInnovationCovariance |
Ludwigfr | 12:1e80471c5c6c | 1500 | compositeInnovationCovariance3x3Inverse.fillWithInverse(compositeInnovationCovariance3x3); |
Ludwigfr | 12:1e80471c5c6c | 1501 | pc.printf("\r\n111:calcul compositeInnovationCovariance3x3Inverse passed"); |
Ludwigfr | 12:1e80471c5c6c | 1502 | //compute KalmanGain=covariancePositionEstimationKplus1K*compositeMeasurementJacobianTranspose*Inverse(compositeInnovationCovariance) |
Ludwigfr | 12:1e80471c5c6c | 1503 | tempKalmanGain3X3.fillByMultiplication(covariancePositionEstimationKplus1K,compositeMeasurementJacobian3x3Transpose); |
Ludwigfr | 12:1e80471c5c6c | 1504 | kalmanGain3X3.fillByMultiplication(tempKalmanGain3X3,compositeInnovationCovariance3x3Inverse); |
Ludwigfr | 12:1e80471c5c6c | 1505 | pc.printf("\r\n111:calcul kalmanGain3X3 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1506 | //get the transpose of the kalman gain |
Ludwigfr | 12:1e80471c5c6c | 1507 | kalmanGain3X3Transpose.fillWithTranspose(kalmanGain3X3); |
Ludwigfr | 12:1e80471c5c6c | 1508 | //update pose estimation=old pose estimation + kalman gain*compositeInnovation |
Ludwigfr | 12:1e80471c5c6c | 1509 | tempPoseKplus1Kplus1.fillByMultiplication(kalmanGain3X3,compositeInnovation3x1); |
Ludwigfr | 12:1e80471c5c6c | 1510 | poseKplus1Kplus1.addition(tempPoseKplus1Kplus1); |
Ludwigfr | 12:1e80471c5c6c | 1511 | pc.printf("\r\n111:calcul poseKplus1Kplus1 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1512 | //compute covariancePositionEstimationKplus1Kplus1=covariancePositionEstimationKplus1K-kalmanGain*compositeInnovationCovariance*KalmanGainTranspose |
Ludwigfr | 12:1e80471c5c6c | 1513 | temp2CovariancePositionEstimationKplus1Kplus13x3.fillByMultiplication(kalmanGain3X3,compositeInnovationCovariance3x3); |
Ludwigfr | 12:1e80471c5c6c | 1514 | tempCovariancePositionEstimationKplus1Kplus13x3.fillByMultiplication(temp2CovariancePositionEstimationKplus1Kplus13x3,kalmanGain3X3Transpose); |
Ludwigfr | 12:1e80471c5c6c | 1515 | covariancePositionEstimationKplus1Kplus1.subtraction(tempCovariancePositionEstimationKplus1Kplus13x3); |
Ludwigfr | 12:1e80471c5c6c | 1516 | pc.printf("\r\n111:calcul covariancePositionEstimationKplus1Kplus1 passed"); |
Ludwigfr | 12:1e80471c5c6c | 1517 | break; |
Ludwigfr | 12:1e80471c5c6c | 1518 | } |
Ludwigfr | 9:1cc27f33d3e1 | 1519 | //update covariancePositionEstimationK =covariancePositionEstimationKplus1Kplus1 |
Ludwigfr | 9:1cc27f33d3e1 | 1520 | this->covariancePositionEstimationK.fillByCopy(covariancePositionEstimationKplus1Kplus1); |
Ludwigfr | 5:19f24c363418 | 1521 | |
Ludwigfr | 12:1e80471c5c6c | 1522 | //pc.printf("\r\nposeKplus1Kplus1 X=%f, Y=%f, theta=%f",poseKplus1Kplus1.data[0][0],poseKplus1Kplus1.data[1][0],poseKplus1Kplus1.data[2][0]); |
Ludwigfr | 9:1cc27f33d3e1 | 1523 | //update pose |
Ludwigfr | 9:1cc27f33d3e1 | 1524 | this->xWorld=poseKplus1Kplus1.data[0][0]; |
Ludwigfr | 9:1cc27f33d3e1 | 1525 | this->yWorld=poseKplus1Kplus1.data[1][0]; |
Ludwigfr | 9:1cc27f33d3e1 | 1526 | this->thetaWorld=poseKplus1Kplus1.data[2][0]; |
Ludwigfr | 5:19f24c363418 | 1527 | |
Ludwigfr | 12:1e80471c5c6c | 1528 | pc.printf("\r\nWith Kalman X=%f, Y=%f, theta=%f",xWorld,yWorld,thetaWorld); |
Ludwigfr | 5:19f24c363418 | 1529 | //try with robot one |
Ludwigfr | 5:19f24c363418 | 1530 | /* |
Ludwigfr | 5:19f24c363418 | 1531 | X=xEstimatedKNext; |
Ludwigfr | 5:19f24c363418 | 1532 | Y=yEstimatedKNext; |
Ludwigfr | 5:19f24c363418 | 1533 | theta=thetaWorldEstimatedKNext; |
Ludwigfr | 5:19f24c363418 | 1534 | this->xWorld=-Y; |
Ludwigfr | 5:19f24c363418 | 1535 | this->yWorld=X; |
Ludwigfr | 5:19f24c363418 | 1536 | if(theta >PI/2) |
Ludwigfr | 5:19f24c363418 | 1537 | this->thetaWorld=-PI+(theta-PI/2); |
Ludwigfr | 5:19f24c363418 | 1538 | else |
Ludwigfr | 5:19f24c363418 | 1539 | this->thetaWorld=theta+PI/2; |
Ludwigfr | 5:19f24c363418 | 1540 | |
Ludwigfr | 5:19f24c363418 | 1541 | |
Ludwigfr | 5:19f24c363418 | 1542 | this->print_map_with_robot_position(); |
Ludwigfr | 5:19f24c363418 | 1543 | pc.printf("\n\rX= %f",this->xWorld); |
Ludwigfr | 5:19f24c363418 | 1544 | pc.printf("\n\rY= %f",this->yWorld); |
Ludwigfr | 5:19f24c363418 | 1545 | pc.printf("\n\rtheta= %f",this->thetaWorld); |
Ludwigfr | 5:19f24c363418 | 1546 | */ |
Ludwigfr | 5:19f24c363418 | 1547 | //update odometrie X Y theta... |
Ludwigfr | 12:1e80471c5c6c | 1548 | } |
Ludwigfr | 5:19f24c363418 | 1549 | } |
Ludwigfr | 5:19f24c363418 | 1550 | |
Ludwigfr | 10:d0109d7cbe7c | 1551 | void MiniExplorerCoimbra::go_to_point_kalman(float targetXWorld, float targetYWorld) { |
Ludwigfr | 10:d0109d7cbe7c | 1552 | |
Ludwigfr | 10:d0109d7cbe7c | 1553 | float angleError; //angle error |
Ludwigfr | 10:d0109d7cbe7c | 1554 | float d; //distance from target |
Ludwigfr | 10:d0109d7cbe7c | 1555 | float angularLeft, angularRight, linear, angular; |
Ludwigfr | 10:d0109d7cbe7c | 1556 | int speed=300; |
Ludwigfr | 5:19f24c363418 | 1557 | |
Ludwigfr | 10:d0109d7cbe7c | 1558 | do { |
Ludwigfr | 10:d0109d7cbe7c | 1559 | //Updating X,Y and theta with the odometry values |
Ludwigfr | 10:d0109d7cbe7c | 1560 | this->OdometriaKalmanFilter(); |
Ludwigfr | 12:1e80471c5c6c | 1561 | //this->myOdometria(); |
Ludwigfr | 12:1e80471c5c6c | 1562 | //pc.printf("\r\nD_cm:%f",D_cm); |
Ludwigfr | 12:1e80471c5c6c | 1563 | //pc.printf("\r\nL_cm:%f",L_cm); |
Ludwigfr | 10:d0109d7cbe7c | 1564 | //Computing angle error and distance towards the target value |
Ludwigfr | 10:d0109d7cbe7c | 1565 | angleError = atan2((targetYWorld-this->yWorld),(targetXWorld-this->xWorld))-this->thetaWorld; |
Ludwigfr | 10:d0109d7cbe7c | 1566 | if(angleError>PI) angleError=-(angleError-PI); |
Ludwigfr | 10:d0109d7cbe7c | 1567 | else if(angleError<-PI) angleError=-(angleError+PI); |
Ludwigfr | 10:d0109d7cbe7c | 1568 | //pc.printf("\n\r error=%f",angleError); |
Ludwigfr | 10:d0109d7cbe7c | 1569 | |
Ludwigfr | 10:d0109d7cbe7c | 1570 | d=this->dist(this->xWorld, this->yWorld, targetXWorld, targetYWorld); |
Ludwigfr | 10:d0109d7cbe7c | 1571 | //pc.printf("\n\r dist=%f/n", d); |
Ludwigfr | 10:d0109d7cbe7c | 1572 | |
Ludwigfr | 10:d0109d7cbe7c | 1573 | //Computing linear and angular velocities |
Ludwigfr | 10:d0109d7cbe7c | 1574 | linear=k_linear*d; |
Ludwigfr | 10:d0109d7cbe7c | 1575 | angular=k_angular*angleError; |
Ludwigfr | 10:d0109d7cbe7c | 1576 | angularLeft=(linear-0.5*this->distanceWheels*angular)/this->radiusWheels; |
Ludwigfr | 10:d0109d7cbe7c | 1577 | angularRight=(linear+0.5*this->distanceWheels*angular)/this->radiusWheels; |
Ludwigfr | 10:d0109d7cbe7c | 1578 | |
Ludwigfr | 10:d0109d7cbe7c | 1579 | //Normalize speed for motors |
Ludwigfr | 10:d0109d7cbe7c | 1580 | if(angularLeft>angularRight) { |
Ludwigfr | 10:d0109d7cbe7c | 1581 | angularRight=speed*angularRight/angularLeft; |
Ludwigfr | 10:d0109d7cbe7c | 1582 | angularLeft=speed; |
Ludwigfr | 10:d0109d7cbe7c | 1583 | } else { |
Ludwigfr | 10:d0109d7cbe7c | 1584 | angularLeft=speed*angularLeft/angularRight; |
Ludwigfr | 10:d0109d7cbe7c | 1585 | angularRight=speed; |
Ludwigfr | 10:d0109d7cbe7c | 1586 | } |
Ludwigfr | 10:d0109d7cbe7c | 1587 | |
Ludwigfr | 12:1e80471c5c6c | 1588 | pc.printf("\n\r X=%f", this->xWorld); |
Ludwigfr | 12:1e80471c5c6c | 1589 | pc.printf("\n\r Y=%f", this->yWorld); |
Ludwigfr | 12:1e80471c5c6c | 1590 | pc.printf("\n\r theta=%f", this->thetaWorld); |
Ludwigfr | 10:d0109d7cbe7c | 1591 | |
Ludwigfr | 10:d0109d7cbe7c | 1592 | //Updating motor velocities |
Ludwigfr | 10:d0109d7cbe7c | 1593 | if(angularLeft>0){ |
Ludwigfr | 10:d0109d7cbe7c | 1594 | leftMotor(1,angularLeft); |
Ludwigfr | 10:d0109d7cbe7c | 1595 | } |
Ludwigfr | 10:d0109d7cbe7c | 1596 | else{ |
Ludwigfr | 10:d0109d7cbe7c | 1597 | leftMotor(0,-angularLeft); |
Ludwigfr | 10:d0109d7cbe7c | 1598 | } |
Ludwigfr | 10:d0109d7cbe7c | 1599 | |
Ludwigfr | 10:d0109d7cbe7c | 1600 | if(angularRight>0){ |
Ludwigfr | 10:d0109d7cbe7c | 1601 | rightMotor(1,angularRight); |
Ludwigfr | 10:d0109d7cbe7c | 1602 | } |
Ludwigfr | 10:d0109d7cbe7c | 1603 | else{ |
Ludwigfr | 10:d0109d7cbe7c | 1604 | rightMotor(0,-angularRight); |
Ludwigfr | 10:d0109d7cbe7c | 1605 | } |
Ludwigfr | 10:d0109d7cbe7c | 1606 | |
Ludwigfr | 10:d0109d7cbe7c | 1607 | //wait(0.5); |
Ludwigfr | 10:d0109d7cbe7c | 1608 | } while(d>5); |
Ludwigfr | 10:d0109d7cbe7c | 1609 | |
Ludwigfr | 10:d0109d7cbe7c | 1610 | //Stop at the end |
Ludwigfr | 10:d0109d7cbe7c | 1611 | leftMotor(1,0); |
Ludwigfr | 10:d0109d7cbe7c | 1612 | rightMotor(1,0); |
Ludwigfr | 10:d0109d7cbe7c | 1613 | } |
Ludwigfr | 10:d0109d7cbe7c | 1614 | |
Ludwigfr | 10:d0109d7cbe7c | 1615 | void MiniExplorerCoimbra::printMatrix(myMatrix mat1){ |
Ludwigfr | 10:d0109d7cbe7c | 1616 | for(int i = 0; i < mat1.nbRow; ++i) { |
Ludwigfr | 10:d0109d7cbe7c | 1617 | for(int j = 0; j < mat1.nbColumn; ++j) { |
Ludwigfr | 10:d0109d7cbe7c | 1618 | pc.printf("\r%f",mat1.data[i][j]); |
Ludwigfr | 10:d0109d7cbe7c | 1619 | } |
Ludwigfr | 10:d0109d7cbe7c | 1620 | pc.printf("\n"); |
Ludwigfr | 10:d0109d7cbe7c | 1621 | } |
Ludwigfr | 12:1e80471c5c6c | 1622 | pc.printf("\r\n"); |
Ludwigfr | 10:d0109d7cbe7c | 1623 | } |