|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |
java.lang.Objectjavaclient.PlayerDevice
javaclient.AbstractPositionDevice
javaclient.PositionInterface
public class PositionInterface
The position interface is used to control mobile robot bases in 2D.
Field Summary | |
---|---|
protected short |
PLAYER_POSITION_GET_GEOM_REQ
|
protected short |
PLAYER_POSITION_MOTOR_POWER_REQ
|
protected short |
PLAYER_POSITION_POSITION_MODE_REQ
|
protected short |
PLAYER_POSITION_POSITION_PID_REQ
|
protected short |
PLAYER_POSITION_RESET_ODOM_REQ
|
protected short |
PLAYER_POSITION_RMP_ACCEL_SCALE
|
protected short |
PLAYER_POSITION_RMP_CURRENT_LIMIT
|
protected short |
PLAYER_POSITION_RMP_GAIN_SCHEDULE
|
protected short |
PLAYER_POSITION_RMP_RST_INT_FOREAFT
|
protected short |
PLAYER_POSITION_RMP_RST_INT_LEFT
|
protected short |
PLAYER_POSITION_RMP_RST_INT_RIGHT
|
protected short |
PLAYER_POSITION_RMP_RST_INT_YAW
|
protected short |
PLAYER_POSITION_RMP_RST_INTEGRATORS
|
protected short |
PLAYER_POSITION_RMP_SHUTDOWN
|
protected short |
PLAYER_POSITION_RMP_TURN_SCALE
|
protected short |
PLAYER_POSITION_RMP_VELOCITY_SCALE
|
protected short |
PLAYER_POSITION_SET_ODOM_REQ
|
protected short |
PLAYER_POSITION_SPEED_PID_REQ
|
protected short |
PLAYER_POSITION_SPEED_PROF_REQ
|
protected short |
PLAYER_POSITION_VELOCITY_MODE_REQ
|
Fields inherited from class javaclient.PlayerDevice |
---|
device, DIFFERENCE_SYNCH_FACTOR, index, is, os, pc, PLAYER_MAX_REQREP_SIZE, PLAYER_STXX, reserved, size, t_sec, t_usec, ts_sec, ts_usec |
Constructor Summary | |
---|---|
PositionInterface(PlayerClient pc,
short indexOfDevice)
Constructor for PositionInterface. |
Method Summary | |
---|---|
PlayerPositionGeomT |
getGeom()
Get the geometry data. |
byte |
getStall()
Get motors status. |
int |
getX()
Get X position in mm. |
int |
getXSpeed()
Get X translational velocity in mm/sec. |
int |
getY()
Get Y position in mm. |
int |
getYaw()
Get Heading in degrees. |
int |
getYawSpeed()
Get angular velocity in degrees/sec. |
int |
getYSpeed()
Get Y translational velocity in mm/sec. |
void |
handleEARMessage()
Handle Error Acknowledgement Response messages. |
void |
handleNARMessage()
Handle Negative Acknowledgement Response messages. |
void |
handleResponse(int size)
Handle acknowledgement response messages (threaded mode). |
boolean |
isGeomReady()
Check if geometry data is available. |
void |
queryGeometry()
Configuration request: Query geometry. |
void |
readData()
Read the position data values (x, y, yaw, xSpeed, ySpeed, yawSpeed, stalls). |
void |
resetOdometry()
Configuration request: Reset odometry. |
void |
setControlMode(int mode)
Configuration request: Change control mode. |
void |
setHeading(int yawT)
Send the heading of the robot. |
void |
setMotorPower(int state)
Configuration request: Motor power. |
void |
setOdometry(int xT,
int yT,
int theta)
Configuration request: Set odometry. |
void |
setPosition(int xP,
int yP,
int yawT)
Send position commands. |
void |
setPosition(int xP,
int yP,
int yawT,
int xS,
int yS,
int yawS,
byte state,
byte type)
The position interface accepts new positions and/or velocities for the robot's motors (drivers may support position control, speed control or both). |
void |
setPositionPIDParams(int kp,
int ki,
int kd)
Configuration request: Set position PID parameters. |
void |
setSegwayRPMparams(byte subtype,
short value)
Configuration request: Segway RMP-specific configuration. |
void |
setSpeed(int speed,
int turnrate)
Set speed and turnrate. |
void |
setSpeed(int speed,
int turnrate,
int sideSpeed)
Set speed, turnrate and sideSpeed. |
void |
setSpeedProfileParams(short sp,
short acc)
Configuration request: Set speed profile parameters. |
void |
setVelocityControl(int mode)
Configuration request: Change velocity control. |
void |
setVelocityPIDParams(int kp,
int ki,
int kd)
Configuration request: Set velocity PID parameters. |
Methods inherited from class javaclient.PlayerDevice |
---|
getTimeForDataSampled_sec, getTimeForDataSampled_usec, getTimeForDataSampled, getTimeForDataSent_sec, getTimeForDataSent_usec, getTimeForDataSent, readHeader, sendHeader |
Methods inherited from class java.lang.Object |
---|
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait |
Field Detail |
---|
protected final short PLAYER_POSITION_GET_GEOM_REQ
protected final short PLAYER_POSITION_MOTOR_POWER_REQ
protected final short PLAYER_POSITION_VELOCITY_MODE_REQ
protected final short PLAYER_POSITION_RESET_ODOM_REQ
protected final short PLAYER_POSITION_POSITION_MODE_REQ
protected final short PLAYER_POSITION_SPEED_PID_REQ
protected final short PLAYER_POSITION_POSITION_PID_REQ
protected final short PLAYER_POSITION_SPEED_PROF_REQ
protected final short PLAYER_POSITION_SET_ODOM_REQ
protected final short PLAYER_POSITION_RMP_VELOCITY_SCALE
protected final short PLAYER_POSITION_RMP_ACCEL_SCALE
protected final short PLAYER_POSITION_RMP_TURN_SCALE
protected final short PLAYER_POSITION_RMP_GAIN_SCHEDULE
protected final short PLAYER_POSITION_RMP_CURRENT_LIMIT
protected final short PLAYER_POSITION_RMP_RST_INTEGRATORS
protected final short PLAYER_POSITION_RMP_SHUTDOWN
protected final short PLAYER_POSITION_RMP_RST_INT_RIGHT
protected final short PLAYER_POSITION_RMP_RST_INT_LEFT
protected final short PLAYER_POSITION_RMP_RST_INT_YAW
protected final short PLAYER_POSITION_RMP_RST_INT_FOREAFT
Constructor Detail |
---|
public PositionInterface(PlayerClient pc, short indexOfDevice)
pc
- a reference to the PlayerClient objectindexOfDevice
- the index of the deviceMethod Detail |
---|
public void readData()
readData
in class PlayerDevice
public void setPosition(int xP, int yP, int yawT, int xS, int yS, int yawS, byte state, byte type)
xP
- X position in mmyP
- Y position in mmyawT
- Yaw in degreesxS
- X translational velocity in mm/secyS
- Y translational velocity in mm/secyawS
- angular velocity in degrees/secstate
- motor state (zero is either off or locked, depending on the driver)type
- command type; 0 = velocity, 1 = positionpublic void setPosition(int xP, int yP, int yawT)
xP
- X position in mmyP
- Y position in mmyawT
- Yaw in degreespublic void setHeading(int yawT)
yawT
- Yaw in degreespublic void setSpeed(int speed, int turnrate)
setSpeed
in class AbstractPositionDevice
speed
- X translational velocity in mm/secturnrate
- angular velocity in degrees/secpublic void setSpeed(int speed, int turnrate, int sideSpeed)
speed
- X translational velocity in mm/secturnrate
- angular velocity in degrees/secsideSpeed
- Y translational velocity in mm/secpublic void queryGeometry()
public boolean isGeomReady()
public PlayerPositionGeomT getGeom()
public int getX()
getX
in class AbstractPositionDevice
public int getY()
getY
in class AbstractPositionDevice
public int getYaw()
getYaw
in class AbstractPositionDevice
public int getXSpeed()
public int getYSpeed()
public int getYawSpeed()
public byte getStall()
public void setMotorPower(int state)
state
- 0 for off, 1 for onpublic void setVelocityControl(int mode)
mode
- driver-specific modepublic void resetOdometry()
public void setControlMode(int mode)
mode
- 0 for velocity mode, 1 for position modepublic void setOdometry(int xT, int yT, int theta)
xT
- X in mmyT
- Y in mtheta
- Heading in degreespublic void setVelocityPIDParams(int kp, int ki, int kd)
kp
- P parameterki
- I parameterkd
- D parameterpublic void setPositionPIDParams(int kp, int ki, int kd)
kp
- P parameterki
- I parameterkd
- D parameterpublic void setSpeedProfileParams(short sp, short acc)
sp
- max speedacc
- max accelerationpublic void setSegwayRPMparams(byte subtype, short value)
subtype
- must be of PLAYER_POSITION_RMP_*value
- holds various values depending on the type of config. See the "Status"
command in the Segway manual.public void handleResponse(int size)
handleResponse
in class PlayerDevice
size
- size of the payloadpublic void handleNARMessage()
handleNARMessage
in class PlayerDevice
public void handleEARMessage()
handleEARMessage
in class PlayerDevice
|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |