javaclient2
Class PlayerClient
java.lang.Object
java.lang.Thread
javaclient2.PlayerClient
- All Implemented Interfaces:
- java.lang.Runnable, PlayerConstants
public class PlayerClient
- extends java.lang.Thread
- implements PlayerConstants
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:
- v2.0 - Player 2.0 supported
- Author:
- Radu Bogdan Rusu, Maxim Batalin, Esben Ostergaard
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 |
Fields inherited from interface javaclient2.structures.PlayerConstants |
MCOM_CHANNEL_LEN, MCOM_DATA_BUFFER_SIZE, MCOM_DATA_LEN, MCOM_N_BUFS, PLAYER_ACTARRAY_ACTSTATE_BRAKED, PLAYER_ACTARRAY_ACTSTATE_IDLE, PLAYER_ACTARRAY_ACTSTATE_MOVING, PLAYER_ACTARRAY_ACTSTATE_STALLED, PLAYER_ACTARRAY_BRAKES_REQ, PLAYER_ACTARRAY_CODE, PLAYER_ACTARRAY_DATA_STATE, PLAYER_ACTARRAY_GET_GEOM_REQ, PLAYER_ACTARRAY_HOME_CMD, PLAYER_ACTARRAY_NUM_ACTUATORS, PLAYER_ACTARRAY_POS_CMD, PLAYER_ACTARRAY_POWER_REQ, PLAYER_ACTARRAY_SPEED_CMD, PLAYER_ACTARRAY_SPEED_REQ, PLAYER_ACTARRAY_STRING, PLAYER_ACTARRAY_TYPE_LINEAR, PLAYER_ACTARRAY_TYPE_ROTARY, PLAYER_AIO_CMD_STATE, PLAYER_AIO_CODE, PLAYER_AIO_DATA_STATE, PLAYER_AIO_MAX_INPUTS, PLAYER_AIO_MAX_OUTPUTS, PLAYER_AIO_STRING, PLAYER_AUDIO_CODE, PLAYER_AUDIO_COMMAND_BUFFER_SIZE, PLAYER_AUDIO_DATA_BUFFER_SIZE, PLAYER_AUDIO_PAIRS, PLAYER_AUDIO_STRING, PLAYER_AUDIODSP_CODE, PLAYER_AUDIODSP_DATA_TONES, PLAYER_AUDIODSP_GET_CONFIG, PLAYER_AUDIODSP_MAX_BITSTRING_LEN, PLAYER_AUDIODSP_MAX_FREQS, PLAYER_AUDIODSP_PLAY_CHIRP, PLAYER_AUDIODSP_PLAY_TONE, PLAYER_AUDIODSP_REPLAY, PLAYER_AUDIODSP_SET_CONFIG, PLAYER_AUDIODSP_STRING, PLAYER_AUDIOMIXER_CODE, PLAYER_AUDIOMIXER_GET_LEVELS, PLAYER_AUDIOMIXER_SET_IGAIN, PLAYER_AUDIOMIXER_SET_LINE, PLAYER_AUDIOMIXER_SET_MASTER, PLAYER_AUDIOMIXER_SET_MIC, PLAYER_AUDIOMIXER_SET_OGAIN, PLAYER_AUDIOMIXER_SET_PCM, PLAYER_AUDIOMIXER_STRING, PLAYER_BLINKENLIGHT_CMD_COLOR, PLAYER_BLINKENLIGHT_CMD_DUTYCYCLE, PLAYER_BLINKENLIGHT_CMD_PERIOD, PLAYER_BLINKENLIGHT_CMD_POWER, PLAYER_BLINKENLIGHT_CMD_STATE, PLAYER_BLINKENLIGHT_CODE, PLAYER_BLINKENLIGHT_DATA_STATE, PLAYER_BLINKENLIGHT_STRING, PLAYER_BLOBFINDER_CODE, PLAYER_BLOBFINDER_DATA_BLOBS, PLAYER_BLOBFINDER_MAX_BLOBS, PLAYER_BLOBFINDER_REQ_SET_COLOR, PLAYER_BLOBFINDER_REQ_SET_IMAGER_PARAMS, PLAYER_BLOBFINDER_STRING, PLAYER_BUMPER_CODE, PLAYER_BUMPER_DATA_GEOM, PLAYER_BUMPER_DATA_STATE, PLAYER_BUMPER_GET_GEOM, PLAYER_BUMPER_MAX_SAMPLES, PLAYER_BUMPER_STRING, PLAYER_CAMERA_CODE, PLAYER_CAMERA_COMPRESS_JPEG, PLAYER_CAMERA_COMPRESS_RAW, PLAYER_CAMERA_DATA_STATE, PLAYER_CAMERA_FORMAT_MONO16, PLAYER_CAMERA_FORMAT_MONO8, PLAYER_CAMERA_FORMAT_RGB565, PLAYER_CAMERA_FORMAT_RGB888, PLAYER_CAMERA_IMAGE_HEIGHT, PLAYER_CAMERA_IMAGE_SIZE, PLAYER_CAMERA_IMAGE_WIDTH, PLAYER_CAMERA_STRING, PLAYER_CLOSE_MODE, PLAYER_DATAMODE_PULL, PLAYER_DATAMODE_PUSH, PLAYER_DIO_CMD_VALUES, PLAYER_DIO_CODE, PLAYER_DIO_DATA_VALUES, PLAYER_DIO_STRING, PLAYER_ENERGY_CODE, PLAYER_ENERGY_DATA_STATE, PLAYER_ENERGY_SET_CHARGING_POLICY_REQ, PLAYER_ENERGY_STRING, PLAYER_ERROR_MODE, PLAYER_FIDUCIAL_CODE, PLAYER_FIDUCIAL_DATA_SCAN, PLAYER_FIDUCIAL_MAX_SAMPLES, PLAYER_FIDUCIAL_REQ_GET_FOV, PLAYER_FIDUCIAL_REQ_GET_GEOM, PLAYER_FIDUCIAL_REQ_GET_ID, PLAYER_FIDUCIAL_REQ_SET_FOV, PLAYER_FIDUCIAL_REQ_SET_ID, PLAYER_FIDUCIAL_STRING, PLAYER_GPS_CODE, PLAYER_GPS_DATA_STATE, PLAYER_GPS_STRING, PLAYER_GRAPHICS2D_CODE, PLAYER_GRAPHICS2D_STRING, PLAYER_GRIPPER_CMD_STATE, PLAYER_GRIPPER_CODE, PLAYER_GRIPPER_DATA_STATE, PLAYER_GRIPPER_REQ_GET_GEOM, PLAYER_GRIPPER_STRING, PLAYER_IDENT_STRLEN, PLAYER_IR_CODE, PLAYER_IR_DATA_RANGES, PLAYER_IR_MAX_SAMPLES, PLAYER_IR_POSE, PLAYER_IR_POWER, PLAYER_IR_STRING, PLAYER_JOYSTICK_CODE, PLAYER_JOYSTICK_DATA_STATE, PLAYER_JOYSTICK_STRING, PLAYER_KEYLEN, PLAYER_LASER_CODE, PLAYER_LASER_DATA_SCAN, PLAYER_LASER_DATA_SCANPOSE, PLAYER_LASER_MAX_SAMPLES, PLAYER_LASER_REQ_GET_CONFIG, PLAYER_LASER_REQ_GET_GEOM, PLAYER_LASER_REQ_POWER, PLAYER_LASER_REQ_SET_CONFIG, PLAYER_LASER_STRING, PLAYER_LIMB_BRAKES_REQ, PLAYER_LIMB_CODE, PLAYER_LIMB_DATA, PLAYER_LIMB_GEOM_REQ, PLAYER_LIMB_HOME_CMD, PLAYER_LIMB_POWER_REQ, PLAYER_LIMB_SETPOSE_CMD, PLAYER_LIMB_SETPOSITION_CMD, PLAYER_LIMB_SPEED_REQ, PLAYER_LIMB_STATE_BRAKED, PLAYER_LIMB_STATE_COLL, PLAYER_LIMB_STATE_IDLE, PLAYER_LIMB_STATE_MOVING, PLAYER_LIMB_STATE_OOR, PLAYER_LIMB_STOP_CMD, PLAYER_LIMB_STRING, PLAYER_LIMB_VECMOVE_CMD, PLAYER_LOCALIZE_CODE, PLAYER_LOCALIZE_DATA_HYPOTHS, PLAYER_LOCALIZE_MAX_HYPOTHS, PLAYER_LOCALIZE_PARTICLES_MAX, PLAYER_LOCALIZE_REQ_GET_PARTICLES, PLAYER_LOCALIZE_REQ_SET_POSE, PLAYER_LOCALIZE_STRING, PLAYER_LOG_CODE, PLAYER_LOG_REQ_GET_STATE, PLAYER_LOG_REQ_SET_FILENAME, PLAYER_LOG_REQ_SET_READ_REWIND, PLAYER_LOG_REQ_SET_READ_STATE, PLAYER_LOG_REQ_SET_WRITE_STATE, PLAYER_LOG_STRING, PLAYER_LOG_TYPE_READ, PLAYER_LOG_TYPE_WRITE, PLAYER_MAP_CODE, PLAYER_MAP_DATA_INFO, PLAYER_MAP_MAX_SEGMENTS, PLAYER_MAP_MAX_TILE_SIZE, PLAYER_MAP_REQ_GET_DATA, PLAYER_MAP_REQ_GET_INFO, PLAYER_MAP_REQ_GET_VECTOR, PLAYER_MAP_STRING, PLAYER_MAX_DEVICES, PLAYER_MAX_DRIVER_STRING_LEN, PLAYER_MAX_MESSAGE_SIZE, PLAYER_MAX_REQREP_SIZE, PLAYER_MCOM_CLEAR, PLAYER_MCOM_CODE, PLAYER_MCOM_POP, PLAYER_MCOM_PUSH, PLAYER_MCOM_READ, PLAYER_MCOM_SET_CAPACITY, PLAYER_MCOM_STRING, PLAYER_MSGQUEUE_DEFAULT_MAXLEN, PLAYER_MSGTYPE_CMD, PLAYER_MSGTYPE_DATA, PLAYER_MSGTYPE_REQ, PLAYER_MSGTYPE_RESP_ACK, PLAYER_MSGTYPE_RESP_NACK, PLAYER_MSGTYPE_SYNCH, PLAYER_NOMAD_CODE, PLAYER_NOMAD_STRING, PLAYER_NULL_CODE, PLAYER_NULL_STRING, PLAYER_OPAQUE_CODE, PLAYER_OPAQUE_STRING, PLAYER_OPEN_MODE, PLAYER_PLANNER_CMD_GOAL, PLAYER_PLANNER_CODE, PLAYER_PLANNER_DATA_STATE, PLAYER_PLANNER_MAX_WAYPOINTS, PLAYER_PLANNER_REQ_ENABLE, PLAYER_PLANNER_REQ_GET_WAYPOINTS, PLAYER_PLANNER_STRING, PLAYER_PLAYER_CODE, PLAYER_PLAYER_REQ_ADD_REPLACE_RULE, PLAYER_PLAYER_REQ_AUTH, PLAYER_PLAYER_REQ_DATA, PLAYER_PLAYER_REQ_DATAFREQ, PLAYER_PLAYER_REQ_DATAMODE, PLAYER_PLAYER_REQ_DEV, PLAYER_PLAYER_REQ_DEVLIST, PLAYER_PLAYER_REQ_DRIVERINFO, PLAYER_PLAYER_REQ_IDENT, PLAYER_PLAYER_REQ_NAMESERVICE, PLAYER_PLAYER_STRING, PLAYER_POSITION1D_CMD_STATE, PLAYER_POSITION1D_CODE, PLAYER_POSITION1D_DATA_GEOM, PLAYER_POSITION1D_DATA_STATE, PLAYER_POSITION1D_GET_GEOM, PLAYER_POSITION1D_MOTOR_POWER, PLAYER_POSITION1D_POSITION_MODE, PLAYER_POSITION1D_POSITION_PID, PLAYER_POSITION1D_RESET_ODOM, PLAYER_POSITION1D_SET_ODOM, PLAYER_POSITION1D_SPEED_PID, PLAYER_POSITION1D_SPEED_PROF, PLAYER_POSITION1D_STRING, PLAYER_POSITION1D_VELOCITY_MODE, PLAYER_POSITION2D_CMD_CAR, PLAYER_POSITION2D_CMD_POS, PLAYER_POSITION2D_CMD_VEL, PLAYER_POSITION2D_CODE, PLAYER_POSITION2D_DATA_GEOM, PLAYER_POSITION2D_DATA_STATE, PLAYER_POSITION2D_REQ_GET_GEOM, PLAYER_POSITION2D_REQ_MOTOR_POWER, PLAYER_POSITION2D_REQ_POSITION_MODE, PLAYER_POSITION2D_REQ_POSITION_PID, PLAYER_POSITION2D_REQ_RESET_ODOM, PLAYER_POSITION2D_REQ_SET_ODOM, PLAYER_POSITION2D_REQ_SPEED_PID, PLAYER_POSITION2D_REQ_SPEED_PROF, PLAYER_POSITION2D_REQ_VELOCITY_MODE, PLAYER_POSITION2D_STRING, PLAYER_POSITION3D_CMD_SET_POS, PLAYER_POSITION3D_CMD_SET_VEL, PLAYER_POSITION3D_CODE, PLAYER_POSITION3D_DATA_GEOMETRY, PLAYER_POSITION3D_DATA_STATE, PLAYER_POSITION3D_GET_GEOM, PLAYER_POSITION3D_MOTOR_POWER, PLAYER_POSITION3D_POSITION_MODE, PLAYER_POSITION3D_POSITION_PID, PLAYER_POSITION3D_RESET_ODOM, PLAYER_POSITION3D_SET_ODOM, PLAYER_POSITION3D_SPEED_PID, PLAYER_POSITION3D_SPEED_PROF, PLAYER_POSITION3D_STRING, PLAYER_POSITION3D_VELOCITY_MODE, PLAYER_POWER_CODE, PLAYER_POWER_DATA_STATE, PLAYER_POWER_MASK_CHARGING, PLAYER_POWER_MASK_JOULES, PLAYER_POWER_MASK_PERCENT, PLAYER_POWER_MASK_VOLTS, PLAYER_POWER_MASK_WATTS, PLAYER_POWER_SET_CHARGING_POLICY_REQ, PLAYER_POWER_STRING, PLAYER_PTZ_CMD_STATE, PLAYER_PTZ_CODE, PLAYER_PTZ_DATA_GEOM, PLAYER_PTZ_DATA_STATE, PLAYER_PTZ_MAX_CONFIG_LEN, PLAYER_PTZ_POSITION_CONTROL, PLAYER_PTZ_REQ_AUTOSERVO, PLAYER_PTZ_REQ_CONTROL_MODE, PLAYER_PTZ_REQ_GENERIC, PLAYER_PTZ_REQ_GEOM, PLAYER_PTZ_STRING, PLAYER_PTZ_VELOCITY_CONTROL, PLAYER_RFID_CODE, PLAYER_RFID_DATA, PLAYER_RFID_MAX_GUID, PLAYER_RFID_MAX_TAGS, PLAYER_RFID_REQ_LOCKTAG, PLAYER_RFID_REQ_POWER, PLAYER_RFID_REQ_READTAG, PLAYER_RFID_REQ_WRITETAG, PLAYER_RFID_STRING, PLAYER_SERVICE_ADV_CODE, PLAYER_SERVICE_ADV_STRING, PLAYER_SIMULATION_CODE, PLAYER_SIMULATION_IDENTIFIER_MAXLEN, PLAYER_SIMULATION_REQ_GET_POSE2D, PLAYER_SIMULATION_REQ_SET_POSE2D, PLAYER_SIMULATION_STRING, PLAYER_SONAR_CODE, PLAYER_SONAR_DATA_GEOM, PLAYER_SONAR_DATA_RANGES, PLAYER_SONAR_MAX_SAMPLES, PLAYER_SONAR_REQ_GET_GEOM, PLAYER_SONAR_REQ_POWER, PLAYER_SONAR_STRING, PLAYER_SOUND_CMD_IDX, PLAYER_SOUND_CODE, PLAYER_SOUND_STRING, PLAYER_SPEECH_CMD_SAY, PLAYER_SPEECH_CODE, PLAYER_SPEECH_MAX_STRING_LEN, PLAYER_SPEECH_RECOGNITION_CODE, PLAYER_SPEECH_RECOGNITION_STRING, PLAYER_SPEECH_STRING, PLAYER_TRUTH_CODE, PLAYER_TRUTH_DATA_FIDUCIAL_ID, PLAYER_TRUTH_DATA_POSE, PLAYER_TRUTH_REQ_GET_FIDUCIAL_ID, PLAYER_TRUTH_REQ_SET_FIDUCIAL_ID, PLAYER_TRUTH_REQ_SET_POSE, PLAYER_TRUTH_STRING, PLAYER_WAVEFORM_CODE, PLAYER_WAVEFORM_DATA_MAX, PLAYER_WAVEFORM_DATA_SAMPLE, PLAYER_WAVEFORM_STRING, PLAYER_WIFI_CODE, PLAYER_WIFI_DATA_STATE, PLAYER_WIFI_IWSPY_ADD, PLAYER_WIFI_IWSPY_DEL, PLAYER_WIFI_IWSPY_PING, PLAYER_WIFI_MAC, PLAYER_WIFI_MAX_LINKS, PLAYER_WIFI_MODE_ADHOC, PLAYER_WIFI_MODE_AUTO, PLAYER_WIFI_MODE_INFRA, PLAYER_WIFI_MODE_MASTER, PLAYER_WIFI_MODE_REPEAT, PLAYER_WIFI_MODE_SECOND, PLAYER_WIFI_MODE_UNKNOWN, PLAYER_WIFI_QUAL_DBM, PLAYER_WIFI_QUAL_REL, PLAYER_WIFI_QUAL_UNKNOWN, PLAYER_WIFI_STRING, SPEECH_RECOGNITION_DATA_STRING, SPEECH_RECOGNITION_TEXT_LEN |
Constructor Summary |
PlayerClient(java.lang.String serverName,
int portNumber)
The PlayerClient constructor. |
Method Summary |
void |
close()
The PlayerClient "destructor". |
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. |
void |
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()
[NEEDS TESTING, returns NACK - NOT FINISHED IN PLAYER2]
(warning : player interface discarding message of unsupported subtype 4)
Configuration request: Get data. |
void |
requestDataDeliveryFrequency(int frequency)
[NEEDS TESTING, returns NACK - NOT FINISHED IN PLAYER2]
(warning : player interface discarding message of unsupported subtype 6)
Configuration request: Change data delivery frequency. |
void |
requestDataDeliveryMode(int mode)
[NEEDS TESTING, returns NACK - NOT FINISHED IN PLAYER2]
(warning : player interface discarding message of unsupported subtype 5)
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?] |
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. |
GripperInterface |
requestInterfaceGripper(int index,
int access)
Request a Gripper 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. |
PlannerInterface |
requestInterfacePlanner(int index,
int access)
Request a Planner 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. |
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 |
isDebugging
public static final boolean isDebugging
socket
protected java.net.Socket socket
buffer
protected java.io.BufferedOutputStream buffer
is
protected java.io.DataInputStream is
- The input stream for the socket connected to the player server.
os
protected java.io.DataOutputStream os
- The output stream for the socket connected to the player server.
It's buffered, so remember to flush()!
deviceList
protected java.util.Vector<PlayerDevice> deviceList
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 PlayerportNumber
- the port number of the Player server
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 callsnanos
- 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
requestDeviceList
public void requestDeviceList()
- Request/reply: 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. To request the list, send a null PLAYER_PLAYER_REQ_DEVLIST.
requestDriverInfo
public void requestDriverInfo(PlayerDevAddr device)
- Request/reply: Get the driver name for a particular device.
To get a name, send a PLAYER_PLAYER_REQ_DRIVERINFO request that
specifies the address of the desired device in the addr field. Set
driver_name_count to 0 and leave driver_name empty. The response will
contain the driver name.
- Parameters:
device
- the device
requestData
public void requestData()
- [NEEDS TESTING, returns NACK - NOT FINISHED IN PLAYER2]
(warning : player interface discarding message of unsupported subtype 4)
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(int mode)
- [NEEDS TESTING, returns NACK - NOT FINISHED IN PLAYER2]
(warning : player interface discarding message of unsupported subtype 5)
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(int frequency)
- [NEEDS TESTING, returns NACK - NOT FINISHED IN PLAYER2]
(warning : player interface discarding message of unsupported subtype 6)
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)
- [NEEDS TESTING, OBSOLETE? - NOT IMPLEMENTED IN PLAYER2]
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)
- [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).
- Parameters:
name
- the robot name
requestIdent
public void requestIdent()
- [NOT IMPLEMENTED IN PLAYER2 YET?]
requestAddReplaceRule
public void requestAddReplaceRule(int interf,
int index,
int type,
int subtype,
int replace)
- Configuration request: Add client queue replace rule.
Allows the client to add a replace rule to their server queue. Replace
rules define which messages will be replaced when new data arrives.
If you are not updating frequently from the server then the use of
replace rules for data packets will stop any queue overflow messages.
Each field in the request corresponds to the equivalent field in the
message header (use -1 for a "don't care" value).
- Parameters:
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 messages
readAll
public void readAll()
- Read the Player server replies in non-threaded mode.
isReadyPDDList
public boolean isReadyPDDList()
- Check to see if the Player server replied with a
PLAYER_PLAYER_REQ_DEVLIST successfully.
- Returns:
- true if the PLAYER_PLAYER_REQ_DEVLIST occured, false otherwise
- See Also:
getPDDList()
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()
getPDDList
public PlayerDeviceDevlist getPDDList()
- Get the list of available devices after a
PLAYER_PLAYER_REQ_DEVLIST request.
- Returns:
- an object of PlayerDeviceDevlist type
- See Also:
isReadyPDDList()
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()
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()
isReadyRequestDevice
public boolean isReadyRequestDevice()
- Check to see if the Player server replied with a
PLAYER_PLAYER_REQ_DEV successfully.
- Returns:
- true if the PLAYER_PLAYER_REQ_DEV occured, false
otherwise
requestInterfacePower
public PowerInterface requestInterfacePower(int index,
int access)
- Request a Power device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- a Power device if successful, null otherwise
requestInterfaceGripper
public GripperInterface requestInterfaceGripper(int index,
int access)
- Request a Gripper device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- a Gripper device if successful, null otherwise
requestInterfacePosition2D
public Position2DInterface requestInterfacePosition2D(int index,
int access)
- Request a Position2D device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- a Position2D device if successful, null otherwise
requestInterfaceSonar
public SonarInterface requestInterfaceSonar(int index,
int access)
- Request a Sonar device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- a Sonar device if successful, null otherwise
requestInterfaceLaser
public LaserInterface requestInterfaceLaser(int index,
int access)
- Request a Laser device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- a Laser device if successful, null otherwise
requestInterfaceBlobfinder
public BlobfinderInterface requestInterfaceBlobfinder(int index,
int access)
- Request a Blobfinder device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- a Blobfinder device if successful, null otherwise
requestInterfacePtz
public PtzInterface requestInterfacePtz(int index,
int access)
- Request a Ptz device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- a Ptz device if successful, null otherwise
requestInterfaceFiducial
public FiducialInterface requestInterfaceFiducial(int index,
int access)
- Request a Fiducial device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- a Fiducial device if successful, null otherwise
requestInterfaceSpeech
public SpeechInterface requestInterfaceSpeech(int index,
int access)
- Request a Speech device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- a Speech device if successful, null otherwise
requestInterfaceGPS
public GPSInterface requestInterfaceGPS(int index,
int access)
- Request a GPS device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- a GPS device if successful, null otherwise
requestInterfaceBumper
public BumperInterface requestInterfaceBumper(int index,
int access)
- Request a Bumper device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- a Bumper device if successful, null otherwise
requestInterfaceDIO
public DIOInterface requestInterfaceDIO(int index,
int access)
- Request a DIO device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- a DIO device if successful, null otherwise
requestInterfaceAIO
public AIOInterface requestInterfaceAIO(int index,
int access)
- Request an AIO device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- an AIO device if successful, null otherwise
requestInterfaceIR
public IRInterface requestInterfaceIR(int index,
int access)
- Request an IR device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- an IR device if successful, null otherwise
requestInterfaceWiFi
public WiFiInterface requestInterfaceWiFi(int index,
int access)
- Request a WiFi device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- a WiFi device if successful, null otherwise
requestInterfaceWaveform
public WaveformInterface requestInterfaceWaveform(int index,
int access)
- Request a Waveform device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- a Waveform device if successful, null otherwise
requestInterfaceLocalize
public LocalizeInterface requestInterfaceLocalize(int index,
int access)
- Request a Localize device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- a Localize device if successful, null otherwise
requestInterfaceMCom
public MComInterface requestInterfaceMCom(int index,
int access)
- Request a MComm device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- a MComm device if successful, null otherwise
requestInterfaceSound
public SoundInterface requestInterfaceSound(int index,
int access)
- Request a Sound device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- a Sound device if successful, null otherwise
requestInterfaceAudioDSP
public AudioDSPInterface requestInterfaceAudioDSP(int index,
int access)
- Request an AudioDSP device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- an AudioDSP device if successful, null otherwise
requestInterfaceAudioMixer
public AudioMixerInterface requestInterfaceAudioMixer(int index,
int access)
- Request an AudioMixer device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- an AudioMixer device if successful, null otherwise
requestInterfacePosition3D
public Position3DInterface requestInterfacePosition3D(int index,
int access)
- Request a Position3D device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- a Position3D device if successful, null otherwise
requestInterfaceSimulation
public SimulationInterface requestInterfaceSimulation(int index,
int access)
- Request a Simulation device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- a Simulation device if successful, null otherwise
requestInterfaceBlinkenlight
public BlinkenlightInterface requestInterfaceBlinkenlight(int index,
int access)
- Request a Blinkenlight device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- a Blinkenlight device if successful, null otherwise
requestInterfaceCamera
public CameraInterface requestInterfaceCamera(int index,
int access)
- Request a Camera device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- a Camera device if successful, null otherwise
requestInterfaceMap
public MapInterface requestInterfaceMap(int index,
int access)
- Request a Map device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- a Map device if successful, null otherwise
requestInterfacePlanner
public PlannerInterface requestInterfacePlanner(int index,
int access)
- Request a Planner device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- a Planner device if successful, null otherwise
requestInterfaceLog
public LogInterface requestInterfaceLog(int index,
int access)
- Request a Log device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- a Log device if successful, null otherwise
requestInterfaceJoystick
public JoystickInterface requestInterfaceJoystick(int index,
int access)
- Request a Joystick device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- a Joystick device if successful, null otherwise
requestInterfaceSpeechRecognition
public SpeechRecognitionInterface requestInterfaceSpeechRecognition(int index,
int access)
- Request a Speech Recognition device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- a Speech Recognition device if successful, null otherwise
requestInterfacePosition1D
public Position1DInterface requestInterfacePosition1D(int index,
int access)
- Request a Position1D device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- a Position1D device if successful, null otherwise
requestInterfaceActarray
public ActarrayInterface requestInterfaceActarray(int index,
int access)
- Request an Actarray device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- an Actarray device if successful, null otherwise
requestInterfaceLimb
public LimbInterface requestInterfaceLimb(int index,
int access)
- Request a Limb device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- a Limb device if successful, null otherwise
requestInterfaceRFID
public RFIDInterface requestInterfaceRFID(int index,
int access)
- Request a RFID device.
- Parameters:
index
- the device indexaccess
- access mode
- Returns:
- a RFID device if successful, null otherwise