javaclient
Class MotorInterface

java.lang.Object
  extended by javaclient.PlayerDevice
      extended by javaclient.MotorInterface

public class MotorInterface
extends PlayerDevice

The motor interface is used to control a single motor.

Version:
Author:
Radu Bogdan Rusu

Field Summary
protected  short PLAYER_MOTOR_MOTOR_POWER_REQ
           
protected  short PLAYER_MOTOR_POSITION_MODE_REQ
           
protected  short PLAYER_MOTOR_POSITION_PID_REQ
           
protected  short PLAYER_MOTOR_RESET_ODOM_REQ
           
protected  short PLAYER_MOTOR_SET_GEAR_REDUCTION_REQ
           
protected  short PLAYER_MOTOR_SET_ODOM_REQ
           
protected  short PLAYER_MOTOR_SET_TICS_REQ
           
protected  short PLAYER_MOTOR_SPEED_PID_REQ
           
protected  short PLAYER_MOTOR_SPEED_PROF_REQ
           
protected  short PLAYER_MOTOR_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
MotorInterface(PlayerClient pc, short indexOfDevice)
          Constructor for MotorInterface.
 
Method Summary
 void changePositionControl(byte mode)
          Configuration request: Change position control.
 int getStall()
          Get motors status.
 int getTheta()
          Get theta in mrad (1 milliradian = ~.06 degrees).
 int getThetaSpeed()
          Get angular velocity in mrad/sec.
 void handleEARMessage()
          Handle Error Acknowledgement Response messages.
 void handleNARMessage()
          Handle Negative Acknowledgement Response messages.
 void readData()
          The motor interface returns data regarding the position and velocity of the motor, as well as stall information.
 void resetOdometry()
          Configuration request: Reset odometry.
 void setMotor(int thetaP, int thetaS, int state, int type)
          The motor interface accepts new positions and/or velocities for the motors (drivers may support position control, speed control, or both).
 void setMotorPIDParams(int kp, int ki, int kd)
          Configuration request: Set motor PID parameters.
 void setMotorPower(int state)
          Configuration request: Motor power.
 void setOdometry(int xT, int yT, int theta)
          Configuration request: Set odometry.
 void setSpeedProfileParams(int sp, int acc)
          Configuration request: Set speed profile parameters.

This is usefull in position control mode when you want to ramp your acceleration and deacceleration.
 void setVelocityControl(byte mode)
          Configuration request: Change velocity control mode.
 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, handleResponse, readHeader, sendHeader
 
Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
 

Field Detail

PLAYER_MOTOR_MOTOR_POWER_REQ

protected final short PLAYER_MOTOR_MOTOR_POWER_REQ
See Also:
Constant Field Values

PLAYER_MOTOR_VELOCITY_MODE_REQ

protected final short PLAYER_MOTOR_VELOCITY_MODE_REQ
See Also:
Constant Field Values

PLAYER_MOTOR_RESET_ODOM_REQ

protected final short PLAYER_MOTOR_RESET_ODOM_REQ
See Also:
Constant Field Values

PLAYER_MOTOR_POSITION_MODE_REQ

protected final short PLAYER_MOTOR_POSITION_MODE_REQ
See Also:
Constant Field Values

PLAYER_MOTOR_SPEED_PID_REQ

protected final short PLAYER_MOTOR_SPEED_PID_REQ
See Also:
Constant Field Values

PLAYER_MOTOR_POSITION_PID_REQ

protected final short PLAYER_MOTOR_POSITION_PID_REQ
See Also:
Constant Field Values

PLAYER_MOTOR_SPEED_PROF_REQ

protected final short PLAYER_MOTOR_SPEED_PROF_REQ
See Also:
Constant Field Values

PLAYER_MOTOR_SET_ODOM_REQ

protected final short PLAYER_MOTOR_SET_ODOM_REQ
See Also:
Constant Field Values

PLAYER_MOTOR_SET_GEAR_REDUCTION_REQ

protected final short PLAYER_MOTOR_SET_GEAR_REDUCTION_REQ
See Also:
Constant Field Values

PLAYER_MOTOR_SET_TICS_REQ

protected final short PLAYER_MOTOR_SET_TICS_REQ
See Also:
Constant Field Values
Constructor Detail

MotorInterface

public MotorInterface(PlayerClient pc,
                      short indexOfDevice)
Constructor for MotorInterface.

Parameters:
pc - a reference to the PlayerClient object
indexOfDevice - the index of the device
Method Detail

readData

public void readData()
The motor interface returns data regarding the position and velocity of the motor, as well as stall information.

Overrides:
readData in class PlayerDevice

getTheta

public int getTheta()
Get theta in mrad (1 milliradian = ~.06 degrees).

Returns:
theta in mrad as an integer

getThetaSpeed

public int getThetaSpeed()
Get angular velocity in mrad/sec.

Returns:
angular velocity in mrad/sec as an integer

getStall

public int getStall()
Get motors status.

Returns:
stalled or not?

setMotor

public void setMotor(int thetaP,
                     int thetaS,
                     int state,
                     int type)
The motor interface accepts new positions and/or velocities for the motors (drivers may support position control, speed control, or both).

See the player_motor_cmd structure from player.h

Parameters:
thetaP - theta in mrad
thetaS - angular velocities, in mrad/sec
state - motor state (zero is either off or locked, depending on the driver)
type - command type; 0 = velocity, 1 = position

changePositionControl

public void changePositionControl(byte mode)
Configuration request: Change position control.

Parameters:
mode - 0 for velocity mode, 1 for position mode

setVelocityControl

public void setVelocityControl(byte mode)
Configuration request: Change velocity control mode.

Some motors offer different velocity control modes. It can be changed by sending a request with the format given below, including the appropriate mode. No matter which mode is used, the external client interface to the motor device remains the same.

Parameters:
mode - driver-specific

resetOdometry

public void resetOdometry()
Configuration request: Reset odometry.

Resets the motor's odometry to theta = 0.


setOdometry

public void setOdometry(int xT,
                        int yT,
                        int theta)
Configuration request: Set odometry.

Parameters:
theta - theta in mrad

setVelocityPIDParams

public void setVelocityPIDParams(int kp,
                                 int ki,
                                 int kd)
Configuration request: Set velocity PID parameters.

Parameters:
kp - P parameter
ki - I parameter
kd - D parameter

setMotorPIDParams

public void setMotorPIDParams(int kp,
                              int ki,
                              int kd)
Configuration request: Set motor PID parameters.

Parameters:
kp - P parameter
ki - I parameter
kd - D parameter

setSpeedProfileParams

public void setSpeedProfileParams(int sp,
                                  int acc)
Configuration request: Set speed profile parameters.

This is usefull in position control mode when you want to ramp your acceleration and deacceleration.

Parameters:
sp - max speed
acc - max acceleration

setMotorPower

public void setMotorPower(int state)
Configuration request: Motor power.

On some robots, the motor power can be turned on and off from software.

Be VERY careful with this command! You are very likely to start the robot running across the room at high speed with the battery charger still attached.

Parameters:
state - 0 for off, 1 for on

handleNARMessage

public void handleNARMessage()
Handle Negative Acknowledgement Response messages.

Overrides:
handleNARMessage in class PlayerDevice

handleEARMessage

public void handleEARMessage()
Handle Error Acknowledgement Response messages.

Overrides:
handleEARMessage in class PlayerDevice