|
|||||||||
| PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
| SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD | ||||||||
java.lang.Objectjava.lang.Thread
javaclient2.PlayerClient
public class PlayerClient
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.
| 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 java.util.Vector<PlayerDevice> |
deviceList
|
protected java.io.DataInputStream |
is
The input stream for the socket connected to the player server. |
static boolean |
isDebugging
|
protected java.io.DataOutputStream |
os
The output stream for the socket connected to the player server. |
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". |
java.util.logging.Logger |
getLogger()
Return the Javaclient2 logger. |
PlayerDeviceDriverInfo |
getPDDI()
Get the driver name for a particular device after a PLAYER_PLAYER_DRIVERINFO_REQ request. |
PlayerDeviceDevlist |
getPDDList()
Get the list of available devices after a PLAYER_PLAYER_REQ_DEVLIST request. |
int |
getPortNumber()
Get the port number for the specified robot after a PLAYER_PLAYER_NAMESERVICE_REQ request. |
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 |
isReadyPDDList()
Check to see if the Player server replied with a PLAYER_PLAYER_REQ_DEVLIST successfully. |
boolean |
isReadyPortNumber()
Check to see if the port number has been identified. |
boolean |
isReadyRequestDevice()
Check to see if the Player server replied with a PLAYER_PLAYER_REQ_DEV successfully. |
int |
readAll()
Read the Player server replies in non-threaded mode. |
void |
requestAddReplaceRule(int interf,
int index,
int type,
int subtype,
int replace)
Configuration request: Add client queue replace rule. |
void |
requestAuthentication(byte[] key)
[NEEDS TESTING, OBSOLETE? - NOT IMPLEMENTED IN PLAYER2] Configuration request: Authentication. |
void |
requestData()
Configuration request: Get data. |
void |
requestDataDeliveryMode(int mode)
Configuration request: Change data delivery mode. |
void |
requestDeviceList()
Request/reply: Get the list of available devices. |
void |
requestDriverInfo(PlayerDevAddr device)
Request/reply: Get the driver name for a particular device. |
void |
requestIdent()
[NOT IMPLEMENTED IN PLAYER2 YET?] |
PlayerDevice |
requestInterface(int type,
int index,
int access)
Request a generic device. |
ActarrayInterface |
requestInterfaceActarray(int index,
int access)
Request an Actarray device. |
AIOInterface |
requestInterfaceAIO(int index,
int access)
Request an AIO device. |
AudioDSPInterface |
requestInterfaceAudioDSP(int index,
int access)
Request an AudioDSP device. |
AudioMixerInterface |
requestInterfaceAudioMixer(int index,
int access)
Request an AudioMixer device. |
BlinkenlightInterface |
requestInterfaceBlinkenlight(int index,
int access)
Request a Blinkenlight device. |
BlobfinderInterface |
requestInterfaceBlobfinder(int index,
int access)
Request a Blobfinder device. |
BumperInterface |
requestInterfaceBumper(int index,
int access)
Request a Bumper device. |
CameraInterface |
requestInterfaceCamera(int index,
int access)
Request a Camera device. |
DIOInterface |
requestInterfaceDIO(int index,
int access)
Request a DIO device. |
FiducialInterface |
requestInterfaceFiducial(int index,
int access)
Request a Fiducial device. |
GPSInterface |
requestInterfaceGPS(int index,
int access)
Request a GPS device. |
Graphics2DInterface |
requestInterfaceGraphics2D(int index,
int access)
Request a Graphics2D device. |
Graphics3DInterface |
requestInterfaceGraphics3D(int index,
int access)
Request a Graphics3D device. |
GripperInterface |
requestInterfaceGripper(int index,
int access)
Request a Gripper device. |
HealthInterface |
requestInterfaceHealth(int index,
int access)
Request a Health device. |
IMUInterface |
requestInterfaceIMU(int index,
int access)
Request a IMU device. |
IRInterface |
requestInterfaceIR(int index,
int access)
Request an IR device. |
JoystickInterface |
requestInterfaceJoystick(int index,
int access)
Request a Joystick device. |
LaserInterface |
requestInterfaceLaser(int index,
int access)
Request a Laser device. |
LimbInterface |
requestInterfaceLimb(int index,
int access)
Request a Limb device. |
LocalizeInterface |
requestInterfaceLocalize(int index,
int access)
Request a Localize device. |
LogInterface |
requestInterfaceLog(int index,
int access)
Request a Log device. |
MapInterface |
requestInterfaceMap(int index,
int access)
Request a Map device. |
MComInterface |
requestInterfaceMCom(int index,
int access)
Request a MComm device. |
OpaqueInterface |
requestInterfaceOpaque(int index,
int access)
Request an Opaque device. |
PlannerInterface |
requestInterfacePlanner(int index,
int access)
Request a Planner device. |
PointCloud3DInterface |
requestInterfacePointCloud3D(int index,
int access)
Request a PointCloud3D device. |
Position1DInterface |
requestInterfacePosition1D(int index,
int access)
Request a Position1D device. |
Position2DInterface |
requestInterfacePosition2D(int index,
int access)
Request a Position2D device. |
Position3DInterface |
requestInterfacePosition3D(int index,
int access)
Request a Position3D device. |
PowerInterface |
requestInterfacePower(int index,
int access)
Request a Power device. |
PtzInterface |
requestInterfacePtz(int index,
int access)
Request a Ptz device. |
RFIDInterface |
requestInterfaceRFID(int index,
int access)
Request a RFID device. |
SimulationInterface |
requestInterfaceSimulation(int index,
int access)
Request a Simulation device. |
SonarInterface |
requestInterfaceSonar(int index,
int access)
Request a Sonar device. |
SoundInterface |
requestInterfaceSound(int index,
int access)
Request a Sound device. |
SpeechInterface |
requestInterfaceSpeech(int index,
int access)
Request a Speech device. |
SpeechRecognitionInterface |
requestInterfaceSpeechRecognition(int index,
int access)
Request a Speech Recognition device. |
WaveformInterface |
requestInterfaceWaveform(int index,
int access)
Request a Waveform device. |
WiFiInterface |
requestInterfaceWiFi(int index,
int access)
Request a WiFi device. |
WSNInterface |
requestInterfaceWSN(int index,
int access)
Request a WSN device. |
void |
requestNameService(char[] name)
[NEEDS TESTING, returns NACK - NOT FINISHED IN PLAYER2] (warning : player interface discarding message of unsupported subtype 8) 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 |
|---|
public static final boolean isDebugging
protected java.net.Socket socket
protected java.io.BufferedOutputStream buffer
protected java.io.DataInputStream is
protected java.io.DataOutputStream os
protected java.util.Vector<PlayerDevice> deviceList
| Constructor Detail |
|---|
public PlayerClient(java.lang.String serverName,
int portNumber)
serverName - url of the host running PlayerportNumber - the port number of the Player server| Method Detail |
|---|
public void close()
public void setNotThreaded()
public void runThreaded(long millis,
int nanos)
millis - number of miliseconds to sleep between callsnanos - number of nanoseconds to sleep between callspublic void run()
run in interface java.lang.Runnablerun in class java.lang.Threadpublic java.util.logging.Logger getLogger()
public void requestDeviceList()
public void requestDriverInfo(PlayerDevAddr device)
device - the devicepublic void requestData()
public void requestDataDeliveryMode(int mode)
mode - the requested modepublic void requestAuthentication(byte[] key)
key - the authentication keypublic void requestNameService(char[] name)
name - the robot namepublic void requestIdent()
public void requestAddReplaceRule(int interf,
int index,
int type,
int subtype,
int replace)
interf - interface to set replace rule for (-1 for wildcard)index - index to set replace rule for (-1 for wildcard)type - message type to set replace rule for (-1 for wildcard),
i.e. PLAYER_MSGTYPE_DATAsubtype - message subtype to set replace rule for (-1 for wildcard)replace - should we replace these messagespublic int readAll()
public boolean isReadyPDDList()
getPDDList()public boolean isReadyPDDI()
getPDDI()public PlayerDeviceDevlist getPDDList()
isReadyPDDList()public PlayerDeviceDriverInfo getPDDI()
isReadyPDDI()public int getPortNumber()
requestNameService(char[]),
isReadyPortNumber()public boolean isAuthenticated()
public boolean isReadyPortNumber()
getPortNumber()public boolean isReadyRequestDevice()
public PowerInterface requestInterfacePower(int index,
int access)
index - the device indexaccess - access mode
public GripperInterface requestInterfaceGripper(int index,
int access)
index - the device indexaccess - access mode
public Position2DInterface requestInterfacePosition2D(int index,
int access)
index - the device indexaccess - access mode
public SonarInterface requestInterfaceSonar(int index,
int access)
index - the device indexaccess - access mode
public LaserInterface requestInterfaceLaser(int index,
int access)
index - the device indexaccess - access mode
public BlobfinderInterface requestInterfaceBlobfinder(int index,
int access)
index - the device indexaccess - access mode
public PtzInterface requestInterfacePtz(int index,
int access)
index - the device indexaccess - access mode
public FiducialInterface requestInterfaceFiducial(int index,
int access)
index - the device indexaccess - access mode
public SpeechInterface requestInterfaceSpeech(int index,
int access)
index - the device indexaccess - access mode
public GPSInterface requestInterfaceGPS(int index,
int access)
index - the device indexaccess - access mode
public BumperInterface requestInterfaceBumper(int index,
int access)
index - the device indexaccess - access mode
public DIOInterface requestInterfaceDIO(int index,
int access)
index - the device indexaccess - access mode
public AIOInterface requestInterfaceAIO(int index,
int access)
index - the device indexaccess - access mode
public IRInterface requestInterfaceIR(int index,
int access)
index - the device indexaccess - access mode
public WiFiInterface requestInterfaceWiFi(int index,
int access)
index - the device indexaccess - access mode
public WaveformInterface requestInterfaceWaveform(int index,
int access)
index - the device indexaccess - access mode
public LocalizeInterface requestInterfaceLocalize(int index,
int access)
index - the device indexaccess - access mode
public MComInterface requestInterfaceMCom(int index,
int access)
index - the device indexaccess - access mode
public SoundInterface requestInterfaceSound(int index,
int access)
index - the device indexaccess - access mode
public AudioDSPInterface requestInterfaceAudioDSP(int index,
int access)
index - the device indexaccess - access mode
public AudioMixerInterface requestInterfaceAudioMixer(int index,
int access)
index - the device indexaccess - access mode
public Position3DInterface requestInterfacePosition3D(int index,
int access)
index - the device indexaccess - access mode
public SimulationInterface requestInterfaceSimulation(int index,
int access)
index - the device indexaccess - access mode
public BlinkenlightInterface requestInterfaceBlinkenlight(int index,
int access)
index - the device indexaccess - access mode
public CameraInterface requestInterfaceCamera(int index,
int access)
index - the device indexaccess - access mode
public MapInterface requestInterfaceMap(int index,
int access)
index - the device indexaccess - access mode
public PlannerInterface requestInterfacePlanner(int index,
int access)
index - the device indexaccess - access mode
public LogInterface requestInterfaceLog(int index,
int access)
index - the device indexaccess - access mode
public JoystickInterface requestInterfaceJoystick(int index,
int access)
index - the device indexaccess - access mode
public SpeechRecognitionInterface requestInterfaceSpeechRecognition(int index,
int access)
index - the device indexaccess - access mode
public OpaqueInterface requestInterfaceOpaque(int index,
int access)
index - the device indexaccess - access mode
public Position1DInterface requestInterfacePosition1D(int index,
int access)
index - the device indexaccess - access mode
public ActarrayInterface requestInterfaceActarray(int index,
int access)
index - the device indexaccess - access mode
public LimbInterface requestInterfaceLimb(int index,
int access)
index - the device indexaccess - access mode
public Graphics2DInterface requestInterfaceGraphics2D(int index,
int access)
index - the device indexaccess - access mode
public Graphics3DInterface requestInterfaceGraphics3D(int index,
int access)
index - the device indexaccess - access mode
public RFIDInterface requestInterfaceRFID(int index,
int access)
index - the device indexaccess - access mode
public WSNInterface requestInterfaceWSN(int index,
int access)
index - the device indexaccess - access mode
public HealthInterface requestInterfaceHealth(int index,
int access)
index - the device indexaccess - access mode
public IMUInterface requestInterfaceIMU(int index,
int access)
index - the device indexaccess - access mode
public PointCloud3DInterface requestInterfacePointCloud3D(int index,
int access)
index - the device indexaccess - access mode
public PlayerDevice requestInterface(int type,
int index,
int access)
type - the interface typeindex - the device indexaccess - access mode
|
|||||||||
| PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
| SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD | ||||||||