|
|||||||||
| PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
| SUMMARY: INNER | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD | ||||||||
java.lang.Object | +--tinyvm.rcx.Motor
Abstraction for a motor. Example:
Motor.A.setPower(1);
Motor.C.setPower(7);
Motor.A.forward();
Motor.C.forward();
for (int i = 0; i < 1000; i++) { }
Motor.A.stop();
Motor.C.stop();
| Field Summary | |
static Motor |
A
Motor A. |
static Motor |
B
Motor B. |
static Motor |
C
Motor C. |
| Method Summary | |
void |
backward()
Causes motor to rotate backwards. |
static void |
controlMotor(char aMotor,
int aMode,
int aPower)
Low-level API for controlling a motor. |
void |
flt()
Causes motor to float. |
void |
forward()
Causes motor to rotate forward. |
void |
setPower(int aPower)
Sets motor power to a value between 0 and 7. |
void |
stop()
Causes motor to stop. |
| Methods inherited from class java.lang.Object |
getClass,
toString |
| Field Detail |
public static final Motor A
public static final Motor B
public static final Motor C
| Method Detail |
public final void setPower(int aPower)
A - value in the range [0-7].public final void forward()
public final void backward()
public final void stop()
public final void flt()
public static void controlMotor(char aMotor,
int aMode,
int aPower)
aMotor - The motor id: 'A', 'B' or 'C'.aMode - 1=forward, 2=backward, 3=stop, 4=floataPower - A value in the range [0-7].
|
|||||||||
| PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
| SUMMARY: INNER | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD | ||||||||