Harvey Mudd College
Computer Science 154 - Robotics
Assignment A

Building Keanu

Lab #1 write-up
Alvin Kou, Brian Ji Ho Shin, Fernando Matto
2/05/01

Part 1 - Stateless reactive control -- Survivor!

As mentioned in the introduction, the first test we'll be putting the simulator to is building Keanu-level intelligence. In particular, you should write a function

int computeRotationalVelocity()

that maps the sonar values (the input) to a rotational velocity (the output), so that the robot (whose speed is fixed) survives as long as possible without hitting the walls or obstacles in various environments. The return value of computeRotationalVelocity is an integer, because that is the type expected by the velocity-setting call, vm. (A prototype function is provided in the test file, /cs/cs154/as/A/survivor.cc .

You may use the current rotational and translational velocities of the robot in your computeRotationalVelocity function -- they are accessible as State[39] and State[38], respectively.

Test Worlds

Two worlds in which to test your robot are included in /cs/cs154/as/A. They are shown here. Note that not all angles need be right angles

Survivor Map 1

Survivor Map 2


Results


The general approach we took for the survivor part of Lab 1 was to use weighting to decide on which direction the robot should move. We have a variable that sums the sonar readings with specific weights depending on their location. Sonars on the left side receive a positive value, while sonars on the right side receive a negative value. If the final value is positive, the robot moves towards the left (where there's more space), else it moves towards the right.
   

To avoid overreaction, we do NOT move the robot until the shortest sonar is less than 40 (4 in.). This allows the robot to walk right next to a wall without moving away from it. This seemed to work better than other approaches.
   

The weightings we used give higher priority to sonars in the front of the robot (to avoid direct impact) and an even higher priority to sonars pointing behind the robot (on left and right). The sonars behind the robot indicate which direction to move when it's getting into a corner.

// computeRotationalVelocity Function /////////////////////////////////////////

/*
 * This function computes a rotational velocity in a purely reactive
 * fashion, using just the information in the State vector.
 */

int computeRotationalVelocity()
{
    // Get shortest sonar index
    int shortestSonarIndexLeft;		// Holds the shortest Left Sonar index
    int shortestSonarIndexRight;	// Holds the shortest Right Sonar index
    int shortestIndex;			// Holds the shortest Sonar index
    int direction; 			// Used to compute robot direction

    // Checks sonars 17 through 20 on left
    shortestSonarIndexLeft = getShortestSonarIndex(17, 20);
    // Checks sonars 30 through 32 on right
    shortestSonarIndexRight = getShortestSonarIndex(30, 32);

    // Get shortest sonar
    if(State[shortestSonarIndexLeft] <= State [shortestSonarIndexRight])
    {
      shortestIndex = shortestSonarIndexLeft;
    }
    else
    {
      shortestIndex = shortestSonarIndexRight;
    }

    // Computing sonar distances for robot direction weighting
    // Ignore values above 50 (5 in.)
    int St18 = min(State[18], 50);
    int St19 = min(State[19], 50);
    int St20 = min(State[20], 50);
    int St21 = min(State[21], 50);
    int St22 = min(State[22], 50);
    int St28 = min(State[28], 50);
    int St29 = min(State[29], 50);
    int St30 = min(State[30], 50);
    int St31 = min(State[31], 50);
    int St32 = min(State[32], 50);

    // Direction weights
    // Sonars on front ------> Weight = 5
    //    "    " diagonal ---> Weight = 3
    //    "    " side -------> Weight = 4
    //    "    " right/left -> Weight = 2
    //    "    " behind -----> Weight = 10

    int directionDecide = 5*St18 + 3*St19 + 4*St20 + 2*St21 + 10*St22 - 10*St28 - 2*St29 - 4*St30 - 3*St31 - 5*St32;

    // A positive value -> Turn towards left (more space on left)
    // A negative value -> Turn right
    if (directionDecide < 0)
      direction = -1;
    else
      direction = 1;

    // This avoids over reaction. Turns only when shortest Sonar indicates
    // a risk of hitting the wall
    if (State[shortestIndex] < 40 || State[17] < 40)
      rv = 450;
    else
      rv = 0;

    // Choose direction to move
    rv *= direction;

    return rv;
}

Speeds of 50, 100, 150 and 200 in test world 1: 

Speeds of 50, 100, 150 and 200 in test world 2:

Speeds of 100, 150 and 200 in custom world:
 


Part 2 - Wall/corridor following

Wall-following and corridor following are low-level behaviors essential for higher-level navigation and helpful for just wandering around. (This may have been a technique you used in the previous part of the assignment.)

There is no restriction on how you design your wall-follower, i.e., you need not use purely reactive control. Also, you may stop and start the robot as you see necessary -- there is no requirement to go a particular speed. However, just as survival times measure the fitness of algorithms in part 1 of this assignment, for the wall-followers, running time will determine their fitness -- the faster they can circumnavigate an obstacle, the better, but even a slow moving successful wall follower is better than one which wanders away from the wall or continually crashes into it. (See the "robot pentathlon" note, below.)

Test Worlds

Two worlds in which to test your robot are included in /cs/cs154/as/A. They are shown here. For this part of the assignment, you can assume angles will be right angles (or at least close to it). The intent is to build a left-wall follower, but you may intersperse corridor-following (examining sonars on both sides) and right-wall following if you'd like.



Wall following Map 1





Wall following Map 2

In writing up this part of the assignment, be sure to include the following:


Results 
	My approach to this part of the assignment is fairly straight forward.  The algorithm to making the robot move along the wall consists of five steps:
	1.	Move close to the wall
	2.	Turn until the wall is on the left
	3.	Move forward until wall turns or ends and then stop.
	4. 	Turn in the correct direction.
	5.	Go back to step 3 
The first step is very simple, I just make the robot move forward to the wall at speed 200.  When the robot is a distance of 10 from the wall, then I just stop.
The second step, I turn the robot -90 degrees and then stop.
The third and forth step is harder.  There are three cases in whice the robot needs to changes directions. 
	Case 1: 	The wall turns right.  In this case, I just stop the robot and make a -90 degree turn.
	Case 2:	The wall ends.  This is harder because the sensor on the left of the robot will jump dramatically, so proceed to move the robot forward a little bit more and then turn 90 degrees.
	Case 3:	The wall turns to the left.  This is the hardest case.  This is similar to case 2 except we need to keep track of the robot as he makes a 90 degree turn.  First we set a boolean on as he starts turning.  Then as the sensors on the right picks up the wall again, we can turn the boolean off.  This boolean helps the robot so as he finishs he turn, his sensors on the right won't fire off and make him turn again.  If we don't use this boolean, te robot will end up turning infinitly in circles.
The last step just repeats step 3 and 4 forever.  This keeps the robot moving along the wall. 
The code to the wall following function as well as screen shots of the robot trace is below.
// wallFollow Function ////////////////////////////////////////////////////////

/*****************************************************************************/
/* This function sets the appropriate translational and rotational velocities*/
/* the robot to follow the walls.                                            */
/*****************************************************************************/
void wallFollow()
{
  gs();

  /*
   * First move the robot close to the wall.
   */
  while(!foundWall)
    {
      vm(200, 0, 0);
      gs();
      
      if(State[17] <= 10)
	foundWall = true;
    }

  /*
   * Turn the robot to the right and continue.
   */
  while (State [38] != 0)
    {
      vm(0, 0, 0);
      pr(0, -900, -900);
      ws(true, true, true, true);
      while(State[39] != 0)
	{
	  gs();
	  ws(true, true, true, true);
	}  
    }

  /*
   * Move the robot along the wall. 
   */
  while (State[17]>15)
    {
      vm(200, 0, 0);
      gs();
      if ( (State[21] > 25) && (!leftWallEnded) )
	{
	  leftWallEnded = true;
	  while(State [38] != 0)
	    {
	      vm(0, 0, 0);
	      pr(150, 900, 900);
	      ws(true, true, true, true);
	      while(State[39] != 0)
		{
		  gs();
		  ws(true, true, true, true);
		}
	    }
	}

      if ( (State[21] <= 25) && (leftWallEnded == true) )
	leftWallEnded = false;
    }

  if(State[17] <= 15 || State[19] <= 10)
    {
      while (State [38] != 0)
	{
	  vm(0, 0, 0);
	  
	  pr(0, -900, -900);
	  ws(true, true, true, true);
	  while(State[39] != 0)
	    {
	      gs();
	      ws(true, true, true, true);
	    }  
	}
    }
}
Robot traces for map 1 and map 2.