robot
Class Pioneer

java.lang.Object
  extended by device.Device
      extended by robot.Robot
          extended by robot.Pioneer
All Implemented Interfaces:
IDevice, java.lang.Runnable, IPioneer, IRobot
Direct Known Subclasses:
ExploreRobot, NavRobot

public class Pioneer
extends Robot
implements IPioneer

This class represents a minimal or standard configuration of a Pioneer 2DX robot at TAMS laboratory. Specialized classes can inherit from it to add new devices.


Nested Class Summary
 
Nested classes/interfaces inherited from interface robot.external.IPioneer
IPioneer.StateType, IPioneer.viewDirectType
 
Field Summary
(package private)  IPioneer.StateType currentState
           
(package private)  Position lastPosition
           
(package private)  int stuckCounter
           
(package private)  boolean timerIsOccured
          Watchdog timer for stuck checking
 
Fields inherited from class robot.Robot
bloFi, goal, gripper, localizer, logger, planner, posi, position, ranger0, ranger1, rLaser, robotId, rSonar, simu, speed, turnrate
 
Fields inherited from interface robot.external.IPioneer
BEAMCOUNT, COS45, DEGPROBEAM, DIAGOFFSET, DIST_TOLERANCE, FMAX, FMIN, HORZOFFSET, INV_COS45, isDebugDistance, isDebugLaser, isDebugPosition, isDebugSonar, isDebugState, LFMAX, LFMIN, LMAX, LMAXANGLE, LMIN, LPMAX, MAXSPEED, MAXTURNRATE, MINRANGE, MINSPEED, MINTURNRATE, MOUNTOFFSET, RFMAX, RFMIN, RMAX, RMIN, SHAPE_DIST, SONARCOUNT, SONARMAX, STOP_ROT, STOP_WALLFOLLOWDIST, TRACK_ROT, WALLFOLLOWDIST, WALLLOSTDIST, YAW_TOLERANCE
 
Fields inherited from interface device.external.IDevice
DEVICE_ACTARRAY_CODE, DEVICE_AIO_CODE, DEVICE_AUDIO_CODE, DEVICE_AUDIODSP_CODE, DEVICE_AUDIOMIXER_CODE, DEVICE_BLINKENLIGHT_CODE, DEVICE_BLOBFINDER_CODE, DEVICE_BUMPER_CODE, DEVICE_CAMERA_CODE, DEVICE_DEVICE_CODE, DEVICE_DIO_CODE, DEVICE_ENERGY_CODE, DEVICE_FIDUCIAL_CODE, DEVICE_GPS_CODE, DEVICE_GRAPHICS2D_CODE, DEVICE_GRAPHICS3D_CODE, DEVICE_GRIPPER_CODE, DEVICE_HEALTH_CODE, DEVICE_IMU_CODE, DEVICE_IR_CODE, DEVICE_JOYSTICK_CODE, DEVICE_LASER_CODE, DEVICE_LIMB_CODE, DEVICE_LOCALIZE_CODE, DEVICE_LOG_CODE, DEVICE_MAP_CODE, DEVICE_MCOM_CODE, DEVICE_NOMAD_CODE, DEVICE_NULL_CODE, DEVICE_OPAQUE_CODE, DEVICE_PLANNER_CODE, DEVICE_POINTCLOUD3D_CODE, DEVICE_POSITION1D_CODE, DEVICE_POSITION2D_CODE, DEVICE_POSITION3D_CODE, DEVICE_POWER_CODE, DEVICE_PTZ_CODE, DEVICE_RANGER_CODE, DEVICE_RFID_CODE, DEVICE_SERVICE_ADV_CODE, DEVICE_SIMULATION_CODE, DEVICE_SONAR_CODE, DEVICE_SOUND_CODE, DEVICE_SPEECH_CODE, DEVICE_SPEECH_RECOGNITION_CODE, DEVICE_TRUTH_CODE, DEVICE_WAVEFORM_CODE, DEVICE_WIFI_CODE, DEVICE_WSN_CODE
 
Constructor Summary
Pioneer(Device roboDevices)
          Deprecated. Use Pioneer(Device[]) instead. Creates a Pioneer robot object.
Pioneer(Device[] roboDevList)
          Creates a Pioneer robot.
 
Method Summary
(package private)  void commandMotors(double newSpeed, double newTurnrate)
          Sets the motor speed and syncs the underlying positioning device.
(package private)  void debugSensorData()
           
(package private)  double getCollisionAvoid(double checkTurnrate)
          Collision avoidance overrides other turnrate if necessary!
 IPioneer.StateType getCurrentState()
           
(package private)  double getDistance(IPioneer.viewDirectType viewDirection)
          Returns the minimum distance of the given view direction.
(package private)  double getEscapeWhenStuck(double newTurnrate)
           
(package private)  double getLeftWallfollow(double maxTurnrate)
          Plan a left wall follow trajectory.
(package private)  double getMinLasRange(int minAngle, int maxAngle)
          Returns the minimum distance of the given arc.
(package private)  double getSafeSpeed(double maxSpeed)
          Calculates a safe speed regarding collision avoiding obstacles.
(package private)  double getSafeTurnrate(double maxTurnrate)
          Checks if turning the robot is not causing collisions.
(package private)  double[] getSonarRanges()
          If there are less valid range values than @see SONARCOUNT than the array contains fake (max) values.
(package private)  double[] maxSonarValues()
           
 void setCommand()
          Sets the robot into manual mode.
(package private)  void setCurrentState(IPioneer.StateType newCurrentState)
           
 void setWallfollow()
           
 void stop()
          Stops the robot motion immediately.
protected  void update()
          Checks the robot's current state and performs appropriate actions.
(package private)  void updatePosi()
          Updates the motor speed immediately.
(package private)  void updateSpeed(double saveSpeed)
          Tries to set the speed given.
(package private)  void updateStop()
          Stops the motors immediately if not already stopped.
(package private)  void updateTurnrate(double saveTurnrate)
          Tries to set the turnrate given.
 
Methods inherited from class robot.Robot
connectDevices, getBloFi, getGoal, getGripper, getLaser, getLocalizer, getPlanner, getPosi, getPosition, getRobotId, getSimu, getSonar, getSpeed, getTurnrate, setGoal, setPosition, setRobotId, setSpeed, setTurnrate, shutdown, toString
 
Methods inherited from class device.Device
equals, getDevice, getDeviceIterator, getDeviceList, getDeviceListArray, getHost, getId, getIndex, getLogger, getPort, getSleepTime, getThreadName, isInList, isRunning, isSupported, isThreaded, matches, matchesList, run, runThreaded, setDeviceList, setHost, setName, setPort, setSleepTime
 
Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, wait, wait, wait
 

Field Detail

currentState

IPioneer.StateType currentState

timerIsOccured

boolean timerIsOccured
Watchdog timer for stuck checking


lastPosition

Position lastPosition

stuckCounter

int stuckCounter
Constructor Detail

Pioneer

public Pioneer(Device roboDevices)
Deprecated. Use Pioneer(Device[]) instead. Creates a Pioneer robot object.

Parameters:
roboDevices - The robot devices this robot can access.

Pioneer

public Pioneer(Device[] roboDevList)
Creates a Pioneer robot.

Parameters:
roboDevList - The device list provided to this robot.
Method Detail

update

protected void update()
Checks the robot's current state and performs appropriate actions. Implements a subsumption architecture for robot behaviors.

Overrides:
update in class Device

getEscapeWhenStuck

double getEscapeWhenStuck(double newTurnrate)

commandMotors

void commandMotors(double newSpeed,
                   double newTurnrate)
Sets the motor speed and syncs the underlying positioning device.

Parameters:
newSpeed - The new speed to command.
newTurnrate - The new turnrate to command.

updatePosi

void updatePosi()
Updates the motor speed immediately.


updateStop

void updateStop()
Stops the motors immediately if not already stopped.


stop

public void stop()
Stops the robot motion immediately.


updateSpeed

void updateSpeed(double saveSpeed)
Tries to set the speed given. The actual speed might be lower due to obstacles.

Parameters:
saveSpeed - The speed to set.

updateTurnrate

void updateTurnrate(double saveTurnrate)
Tries to set the turnrate given. The actual turnrate might be lower due to obstacles.

Parameters:
saveTurnrate - The turnrate to set.

getMinLasRange

final double getMinLasRange(int minAngle,
                            int maxAngle)
Returns the minimum distance of the given arc. Algorithm calculates the average of BEAMCOUNT beams to define a minimum value per degree.

Parameters:
minAngle - Minimum angle to check (degree).
maxAngle - Maximum angle to check (degree).
Returns:
Minimum distance in range.

getSonarRanges

final double[] getSonarRanges()
If there are less valid range values than @see SONARCOUNT than the array contains fake (max) values.

Returns:
The sonar range values.

getDistance

final double getDistance(IPioneer.viewDirectType viewDirection)
Returns the minimum distance of the given view direction. Robot shape shall be considered here by weighted SHAPE_DIST. Derived arcs, sonars and weights from graphic "PioneerShape.fig". NOTE: ALL might be slow due recursion, use it only for debugging!

Parameters:
viewDirection - Robot view direction
Returns:
Minimum distance of requested view Direction.

maxSonarValues

double[] maxSonarValues()
Returns:
An sonar range array containing maximum (fake) range values.

getLeftWallfollow

final double getLeftWallfollow(double maxTurnrate)
Plan a left wall follow trajectory. Calculates the turnrate from range measurement and minimum wall follow distance.

Returns:
The new turnrate regarding the left wall (if any).

getCollisionAvoid

final double getCollisionAvoid(double checkTurnrate)
Collision avoidance overrides other turnrate if necessary! May change turnrate or current state. Biased by left wall following


getSafeSpeed

final double getSafeSpeed(double maxSpeed)
Calculates a safe speed regarding collision avoiding obstacles. The Speed will be zero if to near to any obstacle.

Parameters:
maxSpeed - The speed being trying to set.
Returns:
The safe speed.

getSafeTurnrate

final double getSafeTurnrate(double maxTurnrate)
Checks if turning the robot is not causing collisions. Implements more or less a rotation policy which decides depending on obstacles at the 4 robot edge surounding spots To not interfere to heavy to overall behaviour turnrate is only inverted (or set to zero)

Returns:
Safe turnrate.

getCurrentState

public IPioneer.StateType getCurrentState()
Returns:
the currentState

setCurrentState

void setCurrentState(IPioneer.StateType newCurrentState)
Parameters:
newCurrentState - the currentState to set

setWallfollow

public void setWallfollow()

setCommand

public void setCommand()
Sets the robot into manual mode. In this mode the speed and the turnrate of the motors can be modified.


debugSensorData

void debugSensorData()