EDU.gatech.cc.is.abstractrobot
Class SimpleN150Hard

java.lang.Object
  |
  +--EDU.gatech.cc.is.abstractrobot.Simple
        |
        +--EDU.gatech.cc.is.abstractrobot.SimpleN150Hard
Direct Known Subclasses:
CommN150Hard, MultiForageN150Hard

public class SimpleN150Hard
extends Simple
implements SimpleN150, HardObject

SimpleN150Hard implements SimpleN150 for Nomad 150 hardware using the Ndirect class. You should see the specifications in SimpleN150 and Ndirect class documentation for details.

Copyright (c)1998 Tucker Balch

See Also:
SimpleN150, Ndirect

Field Summary
protected  double base_speed
           
protected  double cycles
           
protected static boolean DEBUG
           
protected  double desired_heading
           
protected  double desired_speed
           
protected  int hard_command
           
protected  boolean in_reverse
           
protected  boolean keep_running
           
protected  Vec2[] last_Obstacles
           
protected  Vec2 last_Position
           
protected  double last_SteerHeading
           
protected  double last_TurretHeading
           
protected  Ndirect nomad150_hardware
           
protected  int num_Obstacles
           
protected  int obstacle_rangeInch
           
protected  double old_desired_heading
           
protected  double old_desired_turret_heading
           
protected  int old_hard_command
           
protected  double run_time_sum
           
protected  int[] sonar_raw_data
           
protected  double time_sum
           
 
Fields inherited from class EDU.gatech.cc.is.abstractrobot.Simple
dictionary, displayVectors, unique_id
 
Fields inherited from interface EDU.gatech.cc.is.abstractrobot.SimpleN150
MAX_STEER, MAX_TRANSLATION, MAX_TURRET, RADIUS, SONAR_RADIUS
 
Constructor Summary
SimpleN150Hard(int serial_port, int baud)
          Instantiate a SimpleN150Hard object.
 
Method Summary
 java.awt.Color getBackgroundColor()
          Gets the background color of the robot.
 java.awt.Color getForegroundColor()
          Gets the foreground color of the robot.
 Vec2[] getObstacles(long timestamp)
          Get an array of Vec2s that point egocentrically from the center of the robot to the obstacles currently sensed by the bumpers and sonars.
 Vec2 getPosition(long timestamp)
          Get the position of the robot in global coordinates.
 double getSteerHeading(long timestamp)
          Get the current heading of the steering motor (radians).
 long getTime()
          Gets time elapsed since the robot was instantiated.
 double getTurretHeading(long timestamp)
          Get the current heading of the turret motor.
 void quit()
          Quit the I/O thread.
 void resetPosition(Vec2 p)
          Reset the odometry of the robot in global coordinates.
 void resetSteerHeading(double heading)
          Reset the steering odometry of the robot in global coordinates.
 void resetTurretHeading(double heading)
          Reset the turret odometry of the robot in global coordinates.
 void setBaseSpeed(double speed)
          Set the base speed for the robot (translation) in meters per second.
 void setDisplayString(java.lang.String s)
          Set the String that is printed on the robot's display.
 void setObstacleMaxRange(double range)
          Set the maximum range at which a sensor reading should be considered an obstacle.
 void setSpeed(long timestamp, double speed)
          Set the desired speed for the robot (translation).
 void setSteerHeading(long timestamp, double heading)
          Set the desired heading for the steering motor.
 void setTurretHeading(long timestamp, double heading)
          Set the desired heading for the turret motor.
 void takeStep()
          Conducts periodic I/O with the robot.
 
Methods inherited from class EDU.gatech.cc.is.abstractrobot.Simple
getDictionary, getID, getID, setDictionary, setID
 
Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
 

Field Detail

nomad150_hardware

protected Ndirect nomad150_hardware

DEBUG

protected static final boolean DEBUG

cycles

protected double cycles

run_time_sum

protected double run_time_sum

time_sum

protected double time_sum

keep_running

protected boolean keep_running

old_desired_heading

protected double old_desired_heading

old_desired_turret_heading

protected double old_desired_turret_heading

hard_command

protected int hard_command

old_hard_command

protected int old_hard_command

sonar_raw_data

protected int[] sonar_raw_data

last_Obstacles

protected Vec2[] last_Obstacles

num_Obstacles

protected int num_Obstacles

obstacle_rangeInch

protected int obstacle_rangeInch

last_Position

protected Vec2 last_Position

last_SteerHeading

protected double last_SteerHeading

in_reverse

protected boolean in_reverse

desired_heading

protected double desired_heading

last_TurretHeading

protected double last_TurretHeading

desired_speed

protected double desired_speed

base_speed

protected double base_speed
Constructor Detail

SimpleN150Hard

public SimpleN150Hard(int serial_port,
                      int baud)
               throws java.lang.Exception
Instantiate a SimpleN150Hard object. You should only instantiate one of these per robot connected to your computer. Standard call is SimpleN150Hard(1,38400);
Parameters:
serial_port - 1 = ttys0 (COM1), 2 = ttys1 (COM2) ...
baud - baud rate for communication.
Throws:
java.lang.Exception - If unable to configure the hardware.
Method Detail

takeStep

public void takeStep()
Conducts periodic I/O with the robot. It runs at most every SimpleN150Hard.MIN_CYCLE_TIME milliseconds to gather sensor data from the robot, and issue movement commands.
Specified by:
takeStep in interface HardObject

quit

public void quit()
Quit the I/O thread. Do this only when you are done with the robot!
Overrides:
quit in class Simple

getTime

public long getTime()
Gets time elapsed since the robot was instantiated. Unlike simulation, this is real elapsed time.
Overrides:
getTime in class Simple

getObstacles

public Vec2[] getObstacles(long timestamp)
Get an array of Vec2s that point egocentrically from the center of the robot to the obstacles currently sensed by the bumpers and sonars.
Overrides:
getObstacles in class Simple
Parameters:
timestamp - only get new information if timestamp > than last call or timestamp == -1 .
Returns:
the sensed obstacles.

setObstacleMaxRange

public void setObstacleMaxRange(double range)
Set the maximum range at which a sensor reading should be considered an obstacle. Beyond this range, the readings are ignored. The default range on startup is 1 meter.
Overrides:
setObstacleMaxRange in class Simple
Parameters:
range - the range in meters.

getPosition

public Vec2 getPosition(long timestamp)
Get the position of the robot in global coordinates.
Overrides:
getPosition in class Simple
Parameters:
timestamp - only get new information if timestamp > than last call or timestamp == -1.
Returns:
the position.
See Also:
resetPosition(EDU.gatech.cc.is.util.Vec2)

resetPosition

public void resetPosition(Vec2 p)
Reset the odometry of the robot in global coordinates. This might be done when reliable sensor information provides a very good estimate of the robot's location, or if you are starting the robot in a known location other than (0,0). Do this only if you are certain you're right!
Overrides:
resetPosition in class Simple
Parameters:
position - the new position.
See Also:
getPosition(long)

getSteerHeading

public double getSteerHeading(long timestamp)
Get the current heading of the steering motor (radians).
Overrides:
getSteerHeading in class Simple
Parameters:
timestamp - only get new information if timestamp > than last call or timestamp == -1 .
Returns:
the heading in radians.
See Also:
resetSteerHeading(double), setSteerHeading(long, double)

resetSteerHeading

public void resetSteerHeading(double heading)
Reset the steering odometry of the robot in global coordinates. This might be done when reliable sensor information provides a very good estimate of the robot's heading, or you are starting the robot at a known heading other than 0. Do this only if you are certain you're right! It is also a good idea not to be moving when you do this.
Overrides:
resetSteerHeading in class Simple
Parameters:
heading - the new heading in radians.
See Also:
getSteerHeading(long), setSteerHeading(long, double)

setSteerHeading

public void setSteerHeading(long timestamp,
                            double heading)
Set the desired heading for the steering motor. If the turn is greater than 90 degrees we set the turn to be less than that and move in reverse.
Overrides:
setSteerHeading in class Simple
Parameters:
heading - the heading in radians.
See Also:
getSteerHeading(long), resetSteerHeading(double)

getTurretHeading

public double getTurretHeading(long timestamp)
Get the current heading of the turret motor.
Specified by:
getTurretHeading in interface SimpleN150
Parameters:
timestamp - only get new information if timestamp > than last call or timestamp == -1 .
Returns:
the turret heading in radians.
See Also:
setTurretHeading(long, double), resetTurretHeading(double)

resetTurretHeading

public void resetTurretHeading(double heading)
Reset the turret odometry of the robot in global coordinates. This might be done when reliable sensor information provides a very good estimate of the robot's turret heading. Do this only if you are certain you're right! It is also a good idea not to be moving when you do this.
Specified by:
resetTurretHeading in interface SimpleN150
Parameters:
heading - the new turret heading in radians.
See Also:
getTurretHeading(long), setTurretHeading(long, double)

setTurretHeading

public void setTurretHeading(long timestamp,
                             double heading)
Set the desired heading for the turret motor. We assume the turret is not symmetric, so there is no reverse trick as in the steering motor.
Specified by:
setTurretHeading in interface SimpleN150
Parameters:
heading - the heading in radians.
See Also:
getTurretHeading(long), resetTurretHeading(double)

setSpeed

public void setSpeed(long timestamp,
                     double speed)
Set the desired speed for the robot (translation). The speed must be between 0.0 and 1.0; where 0.0 is stopped and 1.0 is "full blast". It will be clipped to whichever limit it exceeds. The actual commanded speed is zero until the steering motor is close to the desired heading. Use setBaseSpeed to adjust the top speed.
Overrides:
setSpeed in class Simple
Parameters:
timestamp - only get new information if timestamp > than last call
speed - the desired speed from 0 to 1.0, where 1.0 is the base speed.
See Also:
setSteerHeading(long, double), setBaseSpeed(double)

setBaseSpeed

public void setBaseSpeed(double speed)
Set the base speed for the robot (translation) in meters per second. Base speed is how fast the robot will move when setSpeed(1.0) is called. The speed must be between 0 and MAX_TRANSLATION. It will be clipped to whichever limit it exceeds.
Overrides:
setBaseSpeed in class Simple
Parameters:
speed - the desired speed from 0 to 1.0, where 1.0 is the base speed.
See Also:
setSpeed(long, double)

setDisplayString

public void setDisplayString(java.lang.String s)
Set the String that is printed on the robot's display. For real robots, this appears printed on the console.
Overrides:
setDisplayString in class Simple
Parameters:
s - String, the text to display.

getForegroundColor

public java.awt.Color getForegroundColor()
Description copied from interface: SimpleInterface
Gets the foreground color of the robot.
Overrides:
getForegroundColor in class Simple

getBackgroundColor

public java.awt.Color getBackgroundColor()
Description copied from interface: SimpleInterface
Gets the background color of the robot.
Overrides:
getBackgroundColor in class Simple