javaclient
Class PlayerClient

java.lang.Object
  extended by java.lang.Thread
      extended by javaclient.PlayerClient
All Implemented Interfaces:
java.lang.Runnable

public class PlayerClient
extends java.lang.Thread

The PlayerClient is the main Javaclient class. It contains methods for interacting with the player device. The player device represents the server itself, and is used in configuring the behavior of the server. There is only one such device (with index 0) and it is always open.

Version:
Author:
Maxim A. Batalin, Esben H. Ostergaard & Radu Bogdan Rusu

Nested Class Summary
 
Nested classes/interfaces inherited from class java.lang.Thread
java.lang.Thread.State, java.lang.Thread.UncaughtExceptionHandler
 
Field Summary
protected  java.io.BufferedOutputStream buffer
           
protected  PlayerDevice[][] deviceList
           
 java.io.DataInputStream is
          The input stream for the socket connected to the player server.
static boolean isDebugging
           
static int MAX_DEVICES
          maximum devices of the same type
protected static int N_DEVICES
           
 java.io.DataOutputStream os
          The output stream for the socket connected to the player server.
protected static short PLAYER_AIO_CODE
           
static short PLAYER_ALL_MODE
           
protected static short PLAYER_AUDIO_CODE
           
protected static short PLAYER_AUDIODSP_CODE
           
protected static short PLAYER_AUDIOMIXER_CODE
           
protected static short PLAYER_BLINKENLIGHT_CODE
           
protected static short PLAYER_BLOBFINDER_CODE
           
protected static short PLAYER_BUMPER_CODE
           
protected static short PLAYER_CAMERA_CODE
           
static short PLAYER_CLOSE_MODE
           
static byte PLAYER_DATAMODE_PULL_ALL
          Data delivery mode: Only on request (see requestData () request below), send data from ALL subscribed devices, regardless of whether the data is new or old.
static byte PLAYER_DATAMODE_PULL_NEW
          Data delivery mode: Only on request (see requestData () request below), send data only from those subscribed devices that have produced new data since the last time data was pushed to this client.
static byte PLAYER_DATAMODE_PUSH_ALL
          Data delivery mode: Send data at a fixed rate (default 10Hz; see requestDataDeliveryFrequency() below to change the rate) from ALL subscribed devices , regardless of whether the data is new or old.
static byte PLAYER_DATAMODE_PUSH_ASYNC
          Data delivery mode: When a subscribed device produces new data, send it.
static byte PLAYER_DATAMODE_PUSH_NEW
          Data delivery mode: Send data at a fixed rate (default 10Hz; see requestDataDeliveryFrequency() below to change the rate) only from those subscribed devices that have produced new data since the last time data was pushed to this client.
protected static short PLAYER_DESCARTES_CODE
           
protected static short PLAYER_DIO_CODE
           
protected static short PLAYER_ENERGY_CODE
           
static short PLAYER_ERROR_MODE
           
protected static short PLAYER_FIDUCIAL_CODE
           
protected static short PLAYER_GPS_CODE
           
protected static short PLAYER_GRIPPER_CODE
           
protected static short PLAYER_IDAR_CODE
           
protected static short PLAYER_IDARTURRET_CODE
           
protected static short PLAYER_IR_CODE
           
protected static short PLAYER_JOYSTICK_CODE
           
protected static short PLAYER_LASER_CODE
           
protected static short PLAYER_LOCALIZE_CODE
           
protected static short PLAYER_LOG_CODE
           
protected static short PLAYER_MAP_CODE
           
protected static short PLAYER_MAX_DEVICE_STRING_LEN
           
protected static short PLAYER_MAX_REQREP_SIZE
           
protected static short PLAYER_MCOM_CODE
           
protected static short PLAYER_MOTOR_CODE
           
protected static short PLAYER_MSGTYPE_CMD
           
protected static short PLAYER_MSGTYPE_DATA
           
protected static short PLAYER_MSGTYPE_REQ
           
protected static short PLAYER_MSGTYPE_RESP_ACK
           
protected static short PLAYER_MSGTYPE_RESP_ERR
           
protected static short PLAYER_MSGTYPE_RESP_NACK
           
protected static short PLAYER_MSGTYPE_SYNCH
           
protected static short PLAYER_NOMAD_CODE
           
protected static short PLAYER_NULL_CODE
           
protected static short PLAYER_OPAQUE_CODE
           
protected static short PLAYER_PLANNER_CODE
           
protected static short PLAYER_PLAYER_AUTH_REQ
           
protected static short PLAYER_PLAYER_CODE
           
protected static short PLAYER_PLAYER_DATA_REQ
           
protected static short PLAYER_PLAYER_DATAFREQ_REQ
           
protected static short PLAYER_PLAYER_DATAMODE_REQ
           
protected static short PLAYER_PLAYER_DEV_REQ
           
protected static short PLAYER_PLAYER_DEVLIST_REQ
           
protected static short PLAYER_PLAYER_DRIVERINFO_REQ
           
protected static short PLAYER_PLAYER_NAMESERVICE_REQ
           
protected static short PLAYER_POSITION_CODE
           
protected static short PLAYER_POSITION2D_CODE
           
protected static short PLAYER_POSITION3D_CODE
           
protected static short PLAYER_POWER_CODE
           
protected static short PLAYER_PTZ_CODE
           
static short PLAYER_READ_MODE
           
protected static short PLAYER_SERVICE_ADV_CODE
           
protected static short PLAYER_SIMULATION_CODE
           
protected static short PLAYER_SONAR_CODE
           
protected static short PLAYER_SOUND_CODE
           
protected static short PLAYER_SPEECH_CODE
           
protected static short PLAYER_SPEECH_RECOGNITION_CODE
           
protected static short PLAYER_STXX
           
protected static short PLAYER_TRUTH_CODE
           
protected static short PLAYER_WAVEFORM_CODE
           
protected static short PLAYER_WIFI_CODE
           
static short PLAYER_WRITE_MODE
           
protected  java.net.Socket socket
           
 
Fields inherited from class java.lang.Thread
MAX_PRIORITY, MIN_PRIORITY, NORM_PRIORITY
 
Constructor Summary
PlayerClient(java.lang.String serverName, int portNumber)
          The PlayerClient constructor.
 
Method Summary
 void close()
          The PlayerClient "destructor".
 int getI()
          Get the device list index.
 PlayerDeviceDriverInfo getPDDI()
          Get the driver name for a particular device after a PLAYER_PLAYER_DRIVERINFO_REQ request.
 PlayerDeviceDevlistT getPDDT()
          Get the list of available devices after a PLAYER_PLAYER_DEVLIST_REQ request.
 int getPortNumber()
          Get the port number for the specified robot after a PLAYER_PLAYER_NAMESERVICE_REQ request.
 void handleResponse(int size)
          Handle acknowledgement response messages (threaded mode).
 void incI(int increment)
          Increments the device list index.
 boolean isAuthenticated()
          Check to see if the client has authenticated successfully.
 boolean isReadyPDDI()
          Check to see if the Player server replied with a PLAYER_PLAYER_DRIVERINFO_REQ successfully.
 boolean isReadyPDDT()
          Check to see if the Player server replied with a PLAYER_PLAYER_DEVLIST_REQ successfully.
 boolean isReadyPortNumber()
          Check to see if the port number has been identified.
 void readAll()
          Read the Player server replies in non-threaded mode.
 void requestAuthentication(byte[] key)
          Configuration request: Authentication.
 void requestData()
          Configuration request: Get data.
 void requestDataDeliveryFrequency(short frequency)
          Configuration request: Change data delivery frequency.
 void requestDataDeliveryMode(byte mode)
          Configuration request: Change data delivery mode.
 void requestDeviceList()
          Configuration request: Get the list of available devices.
 void requestDriverName(short device)
          Configuration request: Get the driver name for a particular device.
 AIOInterface requestInterfaceAIO(int index, char r)
          Request an AIO device.
 AudioInterface requestInterfaceAudio(int index, char r)
          Request an Audio device.
 AudioDSPInterface requestInterfaceAudioDSP(int index, char r)
          Request an AudioDSP device.
 AudioMixerInterface requestInterfaceAudioMixer(int index, char r)
          Request an AudioMixer device.
 BlinkenlightInterface requestInterfaceBlinkenlight(int index, char r)
          Request a Blinkenlight device.
 BlobfinderInterface requestInterfaceBlobfinder(int index, char r)
          Request a Blobfinder device.
 BumperInterface requestInterfaceBumper(int index, char r)
          Request a Bumper device.
 CameraInterface requestInterfaceCamera(int index, char r)
          Request a Camera device.
 DIOInterface requestInterfaceDIO(int index, char r)
          Request a DIO device.
 EnergyInterface requestInterfaceEnergy(int index, char r)
          Request a Energy device.
 FiducialInterface requestInterfaceFiducial(int index, char r)
          Request a Fiducial device.
 GPSInterface requestInterfaceGPS(int index, char r)
          Request a GPS device.
 GripperInterface requestInterfaceGripper(int index, char r)
          Request a Gripper device.
 IRInterface requestInterfaceIR(int index, char r)
          Request an IR device.
 JoystickInterface requestInterfaceJoystick(int index, char r)
          Request a Joystick device.
 LaserInterface requestInterfaceLaser(int index, char r)
          Request a Laser device.
 LocalizeInterface requestInterfaceLocalize(int index, char r)
          Request a Localize device.
 LogInterface requestInterfaceLog(int index, char r)
          Request a Log device.
 MapInterface requestInterfaceMap(int index, char r)
          Request a Map device.
 MComInterface requestInterfaceMCom(int index, char r)
          Request a MComm device.
 MotorInterface requestInterfaceMotor(int index, char r)
          Request a Motor device.
 NomadInterface requestInterfaceNomad(int index, char r)
          Request a Nomad device.
 PlannerInterface requestInterfacePlanner(int index, char r)
          Request a Planner device.
 PositionInterface requestInterfacePosition(int index, char r)
          Request a Position device.
 Position2DInterface requestInterfacePosition2D(int index, char r)
          Request a Position2D device.
 Position3DInterface requestInterfacePosition3D(int index, char r)
          Request a Position3D device.
 PowerInterface requestInterfacePower(int index, char r)
          Request a Power device.
 PtzInterface requestInterfacePtz(int index, char r)
          Request a Ptz device.
 SimulationInterface requestInterfaceSimulation(int index, char r)
          Request a Simulation device.
 SonarInterface requestInterfaceSonar(int index, char r)
          Request a Sonar device.
 SoundInterface requestInterfaceSound(int index, char r)
          Request a Sound device.
 SpeechInterface requestInterfaceSpeech(int index, char r)
          Request a Speech device.
 SpeechRecognitionInterface requestInterfaceSpeechRecognition(int index, char r)
          Request a Speech Recognition device.
 TruthInterface requestInterfaceTruth(int index, char r)
          Request a Truth device.
 WaveformInterface requestInterfaceWaveform(int index, char r)
          Request a Waveform device.
 WiFiInterface requestInterfaceWiFi(int index, char r)
          Request a WiFi device.
 void requestNameService(char[] name)
          Use nameservice to get the corresponding port for a robot name (only with Stage).
 void run()
          Start the Javaclient thread.
 void runThreaded(long millis, int nanos)
          Start a threaded copy of Javaclient.
 void setNotThreaded()
          Change the mode Javaclient runs to non-threaded.
 
Methods inherited from class java.lang.Thread
activeCount, checkAccess, countStackFrames, currentThread, destroy, dumpStack, enumerate, getAllStackTraces, getContextClassLoader, getDefaultUncaughtExceptionHandler, getId, getName, getPriority, getStackTrace, getState, getThreadGroup, getUncaughtExceptionHandler, holdsLock, interrupt, interrupted, isAlive, isDaemon, isInterrupted, join, join, join, resume, setContextClassLoader, setDaemon, setDefaultUncaughtExceptionHandler, setName, setPriority, setUncaughtExceptionHandler, sleep, sleep, start, stop, stop, suspend, toString, yield
 
Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, wait, wait, wait
 

Field Detail

isDebugging

public static final boolean isDebugging

PLAYER_STXX

protected static final short PLAYER_STXX
See Also:
Constant Field Values

PLAYER_MAX_DEVICE_STRING_LEN

protected static final short PLAYER_MAX_DEVICE_STRING_LEN
See Also:
Constant Field Values

PLAYER_PLAYER_DEVLIST_REQ

protected static final short PLAYER_PLAYER_DEVLIST_REQ
See Also:
Constant Field Values

PLAYER_PLAYER_DRIVERINFO_REQ

protected static final short PLAYER_PLAYER_DRIVERINFO_REQ
See Also:
Constant Field Values

PLAYER_PLAYER_DEV_REQ

protected static final short PLAYER_PLAYER_DEV_REQ
See Also:
Constant Field Values

PLAYER_PLAYER_DATA_REQ

protected static final short PLAYER_PLAYER_DATA_REQ
See Also:
Constant Field Values

PLAYER_PLAYER_DATAMODE_REQ

protected static final short PLAYER_PLAYER_DATAMODE_REQ
See Also:
Constant Field Values

PLAYER_PLAYER_DATAFREQ_REQ

protected static final short PLAYER_PLAYER_DATAFREQ_REQ
See Also:
Constant Field Values

PLAYER_PLAYER_AUTH_REQ

protected static final short PLAYER_PLAYER_AUTH_REQ
See Also:
Constant Field Values

PLAYER_PLAYER_NAMESERVICE_REQ

protected static final short PLAYER_PLAYER_NAMESERVICE_REQ
See Also:
Constant Field Values

PLAYER_MSGTYPE_DATA

protected static final short PLAYER_MSGTYPE_DATA
See Also:
Constant Field Values

PLAYER_MSGTYPE_CMD

protected static final short PLAYER_MSGTYPE_CMD
See Also:
Constant Field Values

PLAYER_MSGTYPE_REQ

protected static final short PLAYER_MSGTYPE_REQ
See Also:
Constant Field Values

PLAYER_MSGTYPE_RESP_ACK

protected static final short PLAYER_MSGTYPE_RESP_ACK
See Also:
Constant Field Values

PLAYER_MSGTYPE_SYNCH

protected static final short PLAYER_MSGTYPE_SYNCH
See Also:
Constant Field Values

PLAYER_MSGTYPE_RESP_NACK

protected static final short PLAYER_MSGTYPE_RESP_NACK
See Also:
Constant Field Values

PLAYER_MSGTYPE_RESP_ERR

protected static final short PLAYER_MSGTYPE_RESP_ERR
See Also:
Constant Field Values

PLAYER_NULL_CODE

protected static final short PLAYER_NULL_CODE
See Also:
Constant Field Values

PLAYER_PLAYER_CODE

protected static final short PLAYER_PLAYER_CODE
See Also:
Constant Field Values

PLAYER_POWER_CODE

protected static final short PLAYER_POWER_CODE
See Also:
Constant Field Values

PLAYER_GRIPPER_CODE

protected static final short PLAYER_GRIPPER_CODE
See Also:
Constant Field Values

PLAYER_POSITION_CODE

protected static final short PLAYER_POSITION_CODE
See Also:
Constant Field Values

PLAYER_SONAR_CODE

protected static final short PLAYER_SONAR_CODE
See Also:
Constant Field Values

PLAYER_LASER_CODE

protected static final short PLAYER_LASER_CODE
See Also:
Constant Field Values

PLAYER_BLOBFINDER_CODE

protected static final short PLAYER_BLOBFINDER_CODE
See Also:
Constant Field Values

PLAYER_PTZ_CODE

protected static final short PLAYER_PTZ_CODE
See Also:
Constant Field Values

PLAYER_AUDIO_CODE

protected static final short PLAYER_AUDIO_CODE
See Also:
Constant Field Values

PLAYER_FIDUCIAL_CODE

protected static final short PLAYER_FIDUCIAL_CODE
See Also:
Constant Field Values

PLAYER_SPEECH_CODE

protected static final short PLAYER_SPEECH_CODE
See Also:
Constant Field Values

PLAYER_GPS_CODE

protected static final short PLAYER_GPS_CODE
See Also:
Constant Field Values

PLAYER_BUMPER_CODE

protected static final short PLAYER_BUMPER_CODE
See Also:
Constant Field Values

PLAYER_TRUTH_CODE

protected static final short PLAYER_TRUTH_CODE
See Also:
Constant Field Values

PLAYER_IDARTURRET_CODE

protected static final short PLAYER_IDARTURRET_CODE
See Also:
Constant Field Values

PLAYER_IDAR_CODE

protected static final short PLAYER_IDAR_CODE
See Also:
Constant Field Values

PLAYER_DESCARTES_CODE

protected static final short PLAYER_DESCARTES_CODE
See Also:
Constant Field Values

PLAYER_DIO_CODE

protected static final short PLAYER_DIO_CODE
See Also:
Constant Field Values

PLAYER_AIO_CODE

protected static final short PLAYER_AIO_CODE
See Also:
Constant Field Values

PLAYER_IR_CODE

protected static final short PLAYER_IR_CODE
See Also:
Constant Field Values

PLAYER_WIFI_CODE

protected static final short PLAYER_WIFI_CODE
See Also:
Constant Field Values

PLAYER_WAVEFORM_CODE

protected static final short PLAYER_WAVEFORM_CODE
See Also:
Constant Field Values

PLAYER_LOCALIZE_CODE

protected static final short PLAYER_LOCALIZE_CODE
See Also:
Constant Field Values

PLAYER_MCOM_CODE

protected static final short PLAYER_MCOM_CODE
See Also:
Constant Field Values

PLAYER_SOUND_CODE

protected static final short PLAYER_SOUND_CODE
See Also:
Constant Field Values

PLAYER_AUDIODSP_CODE

protected static final short PLAYER_AUDIODSP_CODE
See Also:
Constant Field Values

PLAYER_AUDIOMIXER_CODE

protected static final short PLAYER_AUDIOMIXER_CODE
See Also:
Constant Field Values

PLAYER_POSITION3D_CODE

protected static final short PLAYER_POSITION3D_CODE
See Also:
Constant Field Values

PLAYER_SIMULATION_CODE

protected static final short PLAYER_SIMULATION_CODE
See Also:
Constant Field Values

PLAYER_SERVICE_ADV_CODE

protected static final short PLAYER_SERVICE_ADV_CODE
See Also:
Constant Field Values

PLAYER_BLINKENLIGHT_CODE

protected static final short PLAYER_BLINKENLIGHT_CODE
See Also:
Constant Field Values

PLAYER_NOMAD_CODE

protected static final short PLAYER_NOMAD_CODE
See Also:
Constant Field Values

PLAYER_CAMERA_CODE

protected static final short PLAYER_CAMERA_CODE
See Also:
Constant Field Values

PLAYER_MAP_CODE

protected static final short PLAYER_MAP_CODE
See Also:
Constant Field Values

PLAYER_PLANNER_CODE

protected static final short PLAYER_PLANNER_CODE
See Also:
Constant Field Values

PLAYER_LOG_CODE

protected static final short PLAYER_LOG_CODE
See Also:
Constant Field Values

PLAYER_ENERGY_CODE

protected static final short PLAYER_ENERGY_CODE
See Also:
Constant Field Values

PLAYER_MOTOR_CODE

protected static final short PLAYER_MOTOR_CODE
See Also:
Constant Field Values

PLAYER_POSITION2D_CODE

protected static final short PLAYER_POSITION2D_CODE
See Also:
Constant Field Values

PLAYER_JOYSTICK_CODE

protected static final short PLAYER_JOYSTICK_CODE
See Also:
Constant Field Values

PLAYER_SPEECH_RECOGNITION_CODE

protected static final short PLAYER_SPEECH_RECOGNITION_CODE
See Also:
Constant Field Values

PLAYER_OPAQUE_CODE

protected static final short PLAYER_OPAQUE_CODE
See Also:
Constant Field Values

PLAYER_READ_MODE

public static final short PLAYER_READ_MODE
See Also:
Constant Field Values

PLAYER_WRITE_MODE

public static final short PLAYER_WRITE_MODE
See Also:
Constant Field Values

PLAYER_ALL_MODE

public static final short PLAYER_ALL_MODE
See Also:
Constant Field Values

PLAYER_CLOSE_MODE

public static final short PLAYER_CLOSE_MODE
See Also:
Constant Field Values

PLAYER_ERROR_MODE

public static final short PLAYER_ERROR_MODE
See Also:
Constant Field Values

N_DEVICES

protected static int N_DEVICES

MAX_DEVICES

public static int MAX_DEVICES
maximum devices of the same type


PLAYER_MAX_REQREP_SIZE

protected static final short PLAYER_MAX_REQREP_SIZE
See Also:
Constant Field Values

PLAYER_DATAMODE_PUSH_ALL

public static final byte PLAYER_DATAMODE_PUSH_ALL
Data delivery mode: Send data at a fixed rate (default 10Hz; see requestDataDeliveryFrequency() below to change the rate) from ALL subscribed devices , regardless of whether the data is new or old. A PLAYER_MSGTYPE_SYNCH packet follows each set of data. Rarely used.

See Also:
requestDataDeliveryFrequency(short), Constant Field Values

PLAYER_DATAMODE_PULL_ALL

public static final byte PLAYER_DATAMODE_PULL_ALL
Data delivery mode: Only on request (see requestData () request below), send data from ALL subscribed devices, regardless of whether the data is new or old. A PLAYER_MSGTYPE_SYNCH packet follows each set of data. Rarely used.

See Also:
requestData(), Constant Field Values

PLAYER_DATAMODE_PUSH_NEW

public static final byte PLAYER_DATAMODE_PUSH_NEW
Data delivery mode: Send data at a fixed rate (default 10Hz; see requestDataDeliveryFrequency() below to change the rate) only from those subscribed devices that have produced new data since the last time data was pushed to this client. A PLAYER_MSGTYPE_SYNCH packet follows each set of data. This is the default mode.

See Also:
requestDataDeliveryFrequency(short), Constant Field Values

PLAYER_DATAMODE_PULL_NEW

public static final byte PLAYER_DATAMODE_PULL_NEW
Data delivery mode: Only on request (see requestData () request below), send data only from those subscribed devices that have produced new data since the last time data was pushed to this client. Use this mode if your client runs slowly or at an upredictable rate (e.g., a GUI). A PLAYER_MSGTYPE_SYNCH packet follows each set of data.

See Also:
requestData(), Constant Field Values

PLAYER_DATAMODE_PUSH_ASYNC

public static final byte PLAYER_DATAMODE_PUSH_ASYNC
Data delivery mode: When a subscribed device produces new data, send it. This is the lowest-latency delivery mode; when a device produces data, the server (almost) immediately sends it on the client. So the client may receive data at an arbitrarily high rate. PLAYER_MSGTYPE_SYNCH packets are still sent, but at a fixed rate (see requestDataDeliveryFrequency () to change this rate) that is unrelated to rate at which data are delivered from devices.

See Also:
requestDataDeliveryFrequency(short), Constant Field Values

deviceList

protected PlayerDevice[][] deviceList

socket

protected java.net.Socket socket

buffer

protected java.io.BufferedOutputStream buffer

is

public java.io.DataInputStream is
The input stream for the socket connected to the player server.


os

public java.io.DataOutputStream os
The output stream for the socket connected to the player server. It's buffered, so remember to flush()!

Constructor Detail

PlayerClient

public PlayerClient(java.lang.String serverName,
                    int portNumber)
The PlayerClient constructor. Once called, it will create a socket with the Player server running on host servername on port portNumber.

Parameters:
serverName - url of the host running Player
portNumber - the port number of the Player server
Method Detail

close

public void close()
The PlayerClient "destructor". Once called, it will close all the open streams/sockets with the Player server.


setNotThreaded

public void setNotThreaded()
Change the mode Javaclient runs to non-threaded.


runThreaded

public void runThreaded(long millis,
                        int nanos)
Start a threaded copy of Javaclient.

Parameters:
millis - number of miliseconds to sleep between calls
nanos - number of nanoseconds to sleep between calls

run

public void run()
Start the Javaclient thread. Ran automatically from runThreaded ().

Specified by:
run in interface java.lang.Runnable
Overrides:
run in class java.lang.Thread

requestInterfacePower

public PowerInterface requestInterfacePower(int index,
                                            char r)
Request a Power device.

Parameters:
index - the device index
r - access mode
Returns:
a Power device if successful, null otherwise

requestInterfaceGripper

public GripperInterface requestInterfaceGripper(int index,
                                                char r)
Request a Gripper device.

Parameters:
index - the device index
r - access mode
Returns:
a Gripper device if successful, null otherwise

requestInterfacePosition

public PositionInterface requestInterfacePosition(int index,
                                                  char r)
Request a Position device.

Parameters:
index - the device index
r - access mode
Returns:
a Position device if successful, null otherwise

requestInterfaceSonar

public SonarInterface requestInterfaceSonar(int index,
                                            char r)
Request a Sonar device.

Parameters:
index - the device index
r - access mode
Returns:
a Sonar device if successful, null otherwise

requestInterfaceLaser

public LaserInterface requestInterfaceLaser(int index,
                                            char r)
Request a Laser device.

Parameters:
index - the device index
r - access mode
Returns:
a Laser device if successful, null otherwise

requestInterfaceBlobfinder

public BlobfinderInterface requestInterfaceBlobfinder(int index,
                                                      char r)
Request a Blobfinder device.

Parameters:
index - the device index
r - access mode
Returns:
a Blobfinder device if successful, null otherwise

requestInterfacePtz

public PtzInterface requestInterfacePtz(int index,
                                        char r)
Request a Ptz device.

Parameters:
index - the device index
r - access mode
Returns:
a Ptz device if successful, null otherwise

requestInterfaceAudio

public AudioInterface requestInterfaceAudio(int index,
                                            char r)
Request an Audio device.

Parameters:
index - the device index
r - access mode
Returns:
an Audio device if successful, null otherwise

requestInterfaceFiducial

public FiducialInterface requestInterfaceFiducial(int index,
                                                  char r)
Request a Fiducial device.

Parameters:
index - the device index
r - access mode
Returns:
a Fiducial device if successful, null otherwise

requestInterfaceSpeech

public SpeechInterface requestInterfaceSpeech(int index,
                                              char r)
Request a Speech device.

Parameters:
index - the device index
r - access mode
Returns:
a Speech device if successful, null otherwise

requestInterfaceGPS

public GPSInterface requestInterfaceGPS(int index,
                                        char r)
Request a GPS device.

Parameters:
index - the device index
r - access mode
Returns:
a GPS device if successful, null otherwise

requestInterfaceBumper

public BumperInterface requestInterfaceBumper(int index,
                                              char r)
Request a Bumper device.

Parameters:
index - the device index
r - access mode
Returns:
a Bumper device if successful, null otherwise

requestInterfaceTruth

public TruthInterface requestInterfaceTruth(int index,
                                            char r)
Request a Truth device.

Parameters:
index - the device index
r - access mode
Returns:
a Truth device if successful, null otherwise

requestInterfaceDIO

public DIOInterface requestInterfaceDIO(int index,
                                        char r)
Request a DIO device.

Parameters:
index - the device index
r - access mode
Returns:
a DIO device if successful, null otherwise

requestInterfaceAIO

public AIOInterface requestInterfaceAIO(int index,
                                        char r)
Request an AIO device.

Parameters:
index - the device index
r - access mode
Returns:
an AIO device if successful, null otherwise

requestInterfaceIR

public IRInterface requestInterfaceIR(int index,
                                      char r)
Request an IR device.

Parameters:
index - the device index
r - access mode
Returns:
an IR device if successful, null otherwise

requestInterfaceWiFi

public WiFiInterface requestInterfaceWiFi(int index,
                                          char r)
Request a WiFi device.

Parameters:
index - the device index
r - access mode
Returns:
a WiFi device if successful, null otherwise

requestInterfaceWaveform

public WaveformInterface requestInterfaceWaveform(int index,
                                                  char r)
Request a Waveform device.

Parameters:
index - the device index
r - access mode
Returns:
a Waveform device if successful, null otherwise

requestInterfaceLocalize

public LocalizeInterface requestInterfaceLocalize(int index,
                                                  char r)
Request a Localize device.

Parameters:
index - the device index
r - access mode
Returns:
a Localize device if successful, null otherwise

requestInterfaceMCom

public MComInterface requestInterfaceMCom(int index,
                                          char r)
Request a MComm device.

Parameters:
index - the device index
r - access mode
Returns:
a MComm device if successful, null otherwise

requestInterfaceSound

public SoundInterface requestInterfaceSound(int index,
                                            char r)
Request a Sound device.

Parameters:
index - the device index
r - access mode
Returns:
a Sound device if successful, null otherwise

requestInterfaceAudioDSP

public AudioDSPInterface requestInterfaceAudioDSP(int index,
                                                  char r)
Request an AudioDSP device.

Parameters:
index - the device index
r - access mode
Returns:
an AudioDSP device if successful, null otherwise

requestInterfaceAudioMixer

public AudioMixerInterface requestInterfaceAudioMixer(int index,
                                                      char r)
Request an AudioMixer device.

Parameters:
index - the device index
r - access mode
Returns:
an AudioMixer device if successful, null otherwise

requestInterfacePosition3D

public Position3DInterface requestInterfacePosition3D(int index,
                                                      char r)
Request a Position3D device.

Parameters:
index - the device index
r - access mode
Returns:
a Position3D device if successful, null otherwise

requestInterfaceSimulation

public SimulationInterface requestInterfaceSimulation(int index,
                                                      char r)
Request a Simulation device.

Parameters:
index - the device index
r - access mode
Returns:
a Simulation device if successful, null otherwise

requestInterfaceBlinkenlight

public BlinkenlightInterface requestInterfaceBlinkenlight(int index,
                                                          char r)
Request a Blinkenlight device.

Parameters:
index - the device index
r - access mode
Returns:
a Blinkenlight device if successful, null otherwise

requestInterfaceNomad

public NomadInterface requestInterfaceNomad(int index,
                                            char r)
Request a Nomad device.

Parameters:
index - the device index
r - access mode
Returns:
a Nomad device if successful, null otherwise

requestInterfaceCamera

public CameraInterface requestInterfaceCamera(int index,
                                              char r)
Request a Camera device.

Parameters:
index - the device index
r - access mode
Returns:
a Camera device if successful, null otherwise

requestInterfaceMap

public MapInterface requestInterfaceMap(int index,
                                        char r)
Request a Map device.

Parameters:
index - the device index
r - access mode
Returns:
a Map device if successful, null otherwise

requestInterfacePlanner

public PlannerInterface requestInterfacePlanner(int index,
                                                char r)
Request a Planner device.

Parameters:
index - the device index
r - access mode
Returns:
a Planner device if successful, null otherwise

requestInterfaceLog

public LogInterface requestInterfaceLog(int index,
                                        char r)
Request a Log device.

Parameters:
index - the device index
r - access mode
Returns:
a Log device if successful, null otherwise

requestInterfaceEnergy

public EnergyInterface requestInterfaceEnergy(int index,
                                              char r)
Request a Energy device.

Parameters:
index - the device index
r - access mode
Returns:
a Energy device if successful, null otherwise

requestInterfaceMotor

public MotorInterface requestInterfaceMotor(int index,
                                            char r)
Request a Motor device.

Parameters:
index - the device index
r - access mode
Returns:
a Motor device if successful, null otherwise

requestInterfacePosition2D

public Position2DInterface requestInterfacePosition2D(int index,
                                                      char r)
Request a Position2D device.

Parameters:
index - the device index
r - access mode
Returns:
a Position2D device if successful, null otherwise

requestInterfaceJoystick

public JoystickInterface requestInterfaceJoystick(int index,
                                                  char r)
Request a Joystick device.

Parameters:
index - the device index
r - access mode
Returns:
a Joystick device if successful, null otherwise

requestInterfaceSpeechRecognition

public SpeechRecognitionInterface requestInterfaceSpeechRecognition(int index,
                                                                    char r)
Request a Speech Recognition device.

Parameters:
index - the device index
r - access mode
Returns:
a Speech Recognition device if successful, null otherwise

requestDeviceList

public void requestDeviceList()
Configuration request: Get the list of available devices.

It's useful for applications such as viewer programs and test suites that tailor behave differently depending on which devices are available.


requestDriverName

public void requestDriverName(short device)
Configuration request: Get the driver name for a particular device.

Parameters:
device - the device identifier

requestData

public void requestData()
Configuration request: Get data.

When the server is in a PLAYER_DATAMODE_PULL_* data delivery mode, the client can request a single round of data by sending a zero-argument request with type code 0x0003. The response will be a zero-length acknowledgement. The client only needs to make this request when a PLAYER_DATAMODE_PULL_* mode is in use.


requestDataDeliveryMode

public void requestDataDeliveryMode(byte mode)
Configuration request: Change data delivery mode.

The Player server supports four data modes, described above. By default, the server operates in PLAYER_DATAMODE_PUSH_NEW mode at a frequency of 10Hz. To switch to a different mode send a request with the format given below. The server's reply will be a zero-length acknowledgement.

Parameters:
mode - the requested mode

requestDataDeliveryFrequency

public void requestDataDeliveryFrequency(short frequency)
Configuration request: Change data delivery frequency.

By default, the fixed frequency for the PUSH data delivery modes is 10Hz; thus a client which makes no configuration changes will receive sensor data approximately every 100ms. The server can send data faster or slower; to change the frequency, send a request with this format. The server's reply will be a zero-length acknowledgement.

Parameters:
frequency - requested frequency in Hz

requestAuthentication

public void requestAuthentication(byte[] key)
Configuration request: Authentication.

If server authentication has been enabled (by providing '-key ' on the command-line; see Command line options); then each client must authenticate itself before otherwise interacting with the server. To authenticate, send a request with this format.

If the key matches the server's key then the client is authenticated, the server will reply with a zero-length acknowledgement, and the client can continue with other operations. If the key does not match, or if the client attempts any other server interactions before authenticating, then the connection will be closed immediately. It is only necessary to authenticate each client once.

Note that this support for authentication is NOT a security mechanism. The keys are always in plain text, both in memory and when transmitted over the network; further, since the key is given on the command-line, there is a very good chance that you can find it in plain text in the process table (in Linux try 'ps -ax | grep player'). Thus you should not use an important password as your key, nor should you rely on Player authentication to prevent bad guys from driving your robots (use a firewall instead). Rather, authentication was introduced into Player to prevent accidentally connecting one's client program to someone else's robot. This kind of accident occurs primarily when Stage is running in a multi-user environment. In this case it is very likely that there is a Player server listening on port 6665, and clients will generally connect to that port by default, unless a specific option is given.

This mechanism was never really used, and may be removed.

Parameters:
key - the authentication key

requestNameService

public void requestNameService(char[] name)
Use nameservice to get the corresponding port for a robot name (only with Stage).

Parameters:
name - the robot name

getI

public int getI()
Get the device list index.

Returns:
device list index as an integer
See Also:
incI(int)

incI

public void incI(int increment)
Increments the device list index.

Parameters:
increment - number of increments
See Also:
getI()

readAll

public void readAll()
Read the Player server replies in non-threaded mode.


handleResponse

public void handleResponse(int size)
Handle acknowledgement response messages (threaded mode).

Parameters:
size - size of the payload

getPDDT

public PlayerDeviceDevlistT getPDDT()
Get the list of available devices after a PLAYER_PLAYER_DEVLIST_REQ request.

Returns:
an object of PlayerDeviceDevlistT type
See Also:
isReadyPDDT()

getPDDI

public PlayerDeviceDriverInfo getPDDI()
Get the driver name for a particular device after a PLAYER_PLAYER_DRIVERINFO_REQ request.

Returns:
an object of PlayerDeviceDriverInfo type
See Also:
isReadyPDDI()

getPortNumber

public int getPortNumber()
Get the port number for the specified robot after a PLAYER_PLAYER_NAMESERVICE_REQ request.

Returns:
the port number the specified robot runs on
See Also:
requestNameService(char[]), isReadyPortNumber()

isReadyPDDT

public boolean isReadyPDDT()
Check to see if the Player server replied with a PLAYER_PLAYER_DEVLIST_REQ successfully.

Returns:
true if the PLAYER_PLAYER_DEVLIST_REQ occured, false otherwise
See Also:
getPDDT()

isReadyPDDI

public boolean isReadyPDDI()
Check to see if the Player server replied with a PLAYER_PLAYER_DRIVERINFO_REQ successfully.

Returns:
true if the PLAYER_PLAYER_DRIVERINFO_REQ occured, false otherwise
See Also:
getPDDI()

isAuthenticated

public boolean isAuthenticated()
Check to see if the client has authenticated successfully.

Returns:
true if client has authenticated, false otherwise

isReadyPortNumber

public boolean isReadyPortNumber()
Check to see if the port number has been identified.

Returns:
true if the port is ready to be read, false otherwise
See Also:
getPortNumber()