|
|||||||||
| PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
| SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD | ||||||||
java.lang.Objectjavaclient2.extra.Controller
javaclient2.extra.PIDController
javaclient2.extra.HeadingControl
public class HeadingControl
Heading control interface for Position, Position2D and Position3D Player interfaces. Uses methods from both player interfaces and PIDController.
| Field Summary |
|---|
| Fields inherited from class javaclient2.extra.PIDController |
|---|
kd, ki, kp |
| Fields inherited from class javaclient2.extra.Controller |
|---|
currE, eSum, goal, lastE |
| Constructor Summary | |
|---|---|
HeadingControl(AbstractPositionDevice pd)
Constructor for HeadingControl. |
|
HeadingControl(AbstractPositionDevice pd,
int minC,
int maxC)
Constructor for HeadingControl. |
|
HeadingControl(AbstractPositionDevice pd,
int kp,
int ki,
int kd)
Constructor for HeadingControl. |
|
HeadingControl(AbstractPositionDevice pd,
int minC,
int maxC,
int kp,
int ki,
int kd)
Constructor for HeadingControl. |
|
| Method Summary | |
|---|---|
float |
getCommand(float currentOutput)
Calculate and return the controller's command for the controlled system. |
void |
setAllowedError(float err)
Set the maximum allowed error between the final goal and the current position. |
boolean |
setDiffHeading(float angle)
Rotate the robot on spot (differential heading) with a desired heading. |
boolean |
setHeading(float angle)
Rotate the robot on spot (absolute heading) to the desired heading. |
void |
setMaximumCommand(float maxC)
Set the maximum admissible command for the robot's motors. |
void |
setMinimumCommand(float minC)
Set the minimum admissible command for the robot's motors. |
void |
stopRobot()
Stop the robot from moving. |
| Methods inherited from class javaclient2.extra.PIDController |
|---|
getKd, getKi, getKp, setKd, setKi, setKp |
| Methods inherited from class javaclient2.extra.Controller |
|---|
deltaE, setGoal |
| Methods inherited from class java.lang.Object |
|---|
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait |
| Constructor Detail |
|---|
public HeadingControl(AbstractPositionDevice pd)
pd - a reference to a PlayerDevice interface (Position, Position2D
or Position3D).
public HeadingControl(AbstractPositionDevice pd,
int kp,
int ki,
int kd)
pd - a reference to a PlayerDevice interface (Position, Position2D
or Position3D).kp - the proportional constantki - the integral constantkd - the derivative constant
public HeadingControl(AbstractPositionDevice pd,
int minC,
int maxC)
pd - a reference to a PlayerDevice interface (Position, Position2D
or Position3D).minC - minimum admissible command for the robot's motorsmaxC - maximum admissible command for the robot's motors
public HeadingControl(AbstractPositionDevice pd,
int minC,
int maxC,
int kp,
int ki,
int kd)
pd - a reference to a PlayerDevice interface (Position, Position2D
or Position3D).minC - minimum admissible command for the robot's motorsmaxC - maximum admissible command for the robot's motorskp - the proportional constantki - the integral constantkd - the derivative constant| Method Detail |
|---|
public void setMinimumCommand(float minC)
minC - minimum admissible command as an integerpublic void setMaximumCommand(float maxC)
maxC - maximum admissible command as an integerpublic void stopRobot()
public void setAllowedError(float err)
err - maximum allowed error as an integerpublic float getCommand(float currentOutput)
getCommand in class PIDControllercurrentOutput - the current output of the system
public boolean setDiffHeading(float angle)
angle - angle for rotation
public boolean setHeading(float angle)
angle - goal angle
|
|||||||||
| PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
| SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD | ||||||||