diff options
author | Peter Wu <peter@lekensteyn.nl> | 2015-06-17 14:54:55 +0200 |
---|---|---|
committer | Peter Wu <peter@lekensteyn.nl> | 2015-06-17 15:09:25 +0200 |
commit | 9a23407b4c169fa862a95989ed4d274d1623a1bc (patch) | |
tree | 2b04be4cafa869a4cf05ad0826350e193b663a00 | |
parent | c07de296a112ea7e2b0361c4f15ab5cf5370c3cf (diff) | |
download | code-9a23407b4c169fa862a95989ed4d274d1623a1bc.tar.gz |
Attempt to explain timerTurret.
BUG: timerTurret is never reset to 0 once -1.
-rw-r--r-- | Venus_Skeleton/Venus_Skeleton.ino | 27 |
1 files changed, 22 insertions, 5 deletions
diff --git a/Venus_Skeleton/Venus_Skeleton.ino b/Venus_Skeleton/Venus_Skeleton.ino index 14e1ae8..e50709f 100644 --- a/Venus_Skeleton/Venus_Skeleton.ino +++ b/Venus_Skeleton/Venus_Skeleton.ino @@ -105,7 +105,16 @@ int currValDirectionDegree = 0; unsigned long timerMovementStart = 0; unsigned long timerMovementStop = 0; //unsigned long timerInitialSequence = 0; // TODO unused? +/** + * If set to 0, then the turret is not rotating and in a stable position. + * Else the turret is apparently rotating and cannot be stopped. + */ unsigned long timerTurret = 0; +/** + * Always read the sensors on the turret, unless disabled (for example, when + * the measurements become unreliable due to a rotating robot). + */ +bool turretSensingEnabled = true; // Counters int counterInit = 0; @@ -308,7 +317,7 @@ void sensObstacleTurret() { // BE AWARE, LOCALISATION OF OBSTACLE IS y DISTANCE FROM CENTER OF ROBOT // (creates triangle with centerOfRobot, centerOfSensor and Obstacle as its corners) - if (timerTurret == 0) { + if (turretSensingEnabled && timerTurret == 0) { long distance = sensPing(PIN_SENS_OBSTACLE_TURRET); if (data.obstacle_turret_distances[counterTurret] != distance) { data.obstacle_turret_distances[counterTurret] = distance; @@ -349,7 +358,7 @@ void sensSampleTurret() { // BE AWARE, LOCALISATION OF OBSTACLE IS y DISTANCE FROM CENTER OF ROBOT // (creates triangle with centerOfRobot, centerOfSensor and Obstacle as its corners) - if (timerTurret == 0) { + if (turretSensingEnabled && timerTurret == 0) { int i; bool sample = false; @@ -402,7 +411,7 @@ void sensBeaconTurret() { // BE AWARE, LOCALISATION OF OBSTACLE IS y DISTANCE FROM CENTER OF ROBOT // (creates triangle with centerOfRobot, centerOfSensor and Obstacle as its corners) - if (timerTurret == 0) { + if (turretSensingEnabled && timerTurret == 0) { bool beacon; beacon = sensIRRemote(); // SENSORDATA HERE @@ -470,8 +479,9 @@ bool moveTurnTo(int degree) { return true; } - // Make sure turret doesn't move - timerTurret = 1; + // when rotating, the data collected with sensors on the turret becomes + // useless as the orientation is not fixed. + turretSensingEnabled = false; // if movementtimer is not started, start timer or something and initiate movement // else continue movement and return false @@ -512,9 +522,15 @@ bool moveTurnTo(int degree) { if (timerMovementStop < millis()) { DEBUG_PRINT("\n Stop turn move") stopMovement(); + + // reset the ultrasound measurements for (int k = 0; k < NUM_TURRET_DIRECTIONS; k++) { data.obstacle_turret_distances[k] = OBSTACLE_FAR_AWAY; } + + // allow the sensors to be read out again + turretSensingEnabled = true; + // rotation is completed. return true; } @@ -581,6 +597,7 @@ void turnTurretToNext() { timerTurret = millis(); turnTurretTo(deg); } + // If the turret is finished with rotating, mark it as idle. if ((timerTurret + 100) < millis()) { timerTurret = 0; } |