lejos.robotics.navigation
Class DifferentialPilot

java.lang.Object
  extended by lejos.robotics.navigation.DifferentialPilot
All Implemented Interfaces:
ArcMoveController, ArcRotateMoveController, MoveController, MoveProvider, RotateMoveController, RegulatedMotorListener
Direct Known Subclasses:
CompassPilot

public class DifferentialPilot
extends java.lang.Object
implements RegulatedMotorListener, ArcRotateMoveController

The DifferentialPilot class is a software abstraction of the Pilot mechanism of a NXT robot. It contains methods to control robot movements: travel forward or backward in a straight line or a circular path or rotate to a new direction.
This class will only work with two independently controlled motors to steer differentially, so it can rotate within its own footprint (i.e. turn on one spot). It registers as a RegulatedMotorListener with each of its motors. An object of this class assumes that it has exclusive control of its motors. If any other object makes calls to its motors, the results are unpredictable.
This class can be used with robots that have reversed motor design: the robot moves in the direction opposite to the the direction of motor rotation. .
It automatically updates a OdometryPoseProvider which has called the addMoveListener method on this object.
Some methods optionally return immediately so the thread that called it can do things while the robot is moving, such as monitor sensors and call stop().
Handling stalls: If a stall is detected, isStalled() returns true , isMoving() returns false, moveStopped() is called, and, if a blocking method is executing, that method exits. The units of measure for travel distance, speed and acceleration are the units used in specifying the wheel diameter and track width in the constructor.
Example of use of come common methods:

 DifferentialPilot pilot = new DifferentialPilot(2.1f, 4.4f, Motor.A, Motor.C, true);  // parameters in inches
 pilot.setRobotSpeed(30);  // cm per second
 pilot.travel(50);         // cm
 pilot.rotate(-90);        // degree clockwise
 pilot.travel(-50,true);  //  move backward for 50 cm
 while(pilot.isMoving())Thread.yield();
 pilot.rotate(-90);
 pilot.rotateTo(270);
 pilot.steer(-50,180,true); // turn 180 degrees to the right
 waitComplete();            // returns when previous method is complete
 pilot.steer(100);          // turns with left wheel stationary
 Delay.msDelay(1000;
 pilot.stop();
 

Note: A DifferentialPilot robot can simulate a SteeringPilot robot by calling DifferentialPilot.setMinRadius() and setting the value to something greater than zero (perhaps 15 cm).


Field Summary
protected  RegulatedMotor _left
          Left motor..
protected  float _leftDegPerDistance
          Left motor degrees per unit of travel.
protected  RegulatedMotor _outside
          The motor at the outside of the turn.
protected  RegulatedMotor _right
          Right motor.
protected  float _rightDegPerDistance
          Right motor degrees per unit of travel.
protected  Move.MoveType _type
           
 
Fields inherited from interface lejos.robotics.navigation.MoveController
WHEEL_SIZE_NXT1, WHEEL_SIZE_NXT2, WHEEL_SIZE_RCX
 
Fields inherited from interface lejos.robotics.navigation.MoveController
WHEEL_SIZE_NXT1, WHEEL_SIZE_NXT2, WHEEL_SIZE_RCX
 
Constructor Summary
DifferentialPilot(double leftWheelDiameter, double rightWheelDiameter, double trackWidth, RegulatedMotor leftMotor, RegulatedMotor rightMotor, boolean reverse)
          Allocates a DifferentialPilot object, and sets the physical parameters of the NXT robot.
DifferentialPilot(double wheelDiameter, double trackWidth, RegulatedMotor leftMotor, RegulatedMotor rightMotor)
          Allocates a DifferentialPilot object, and sets the physical parameters of the NXT robot.
Assumes Motor.forward() causes the robot to move forward.
DifferentialPilot(double wheelDiameter, double trackWidth, RegulatedMotor leftMotor, RegulatedMotor rightMotor, boolean reverse)
          Allocates a DifferentialPilot object, and sets the physical parameters of the NXT robot.
 
Method Summary
 void addMoveListener(MoveListener m)
          Adds a MoveListener that will be notified of all movement events.
 void arc(double radius, double angle)
          Moves the NXT robot along an arc with a specified radius and angle, after which the robot stops moving.
 void arc(double radius, double angle, boolean immediateReturn)
          Moves the NXT robot along an arc with a specified radius and angle, after which the robot stops moving.
 void arcBackward(double radius)
          Starts the NXT robot moving backward along an arc with a specified radius.
 void arcForward(double radius)
          Starts the NXT robot moving forward along an arc with a specified radius.
 void backward()
          Starts the NXT robot moving backward.
 void forward()
          Starts the NXT robot moving forward.
 float getAngleIncrement()
           
 float getMaxRotateSpeed()
           
 double getMaxTravelSpeed()
          Returns the maximum speed at which this robot is capable of traveling forward and backward.
 double getMinRadius()
          The minimum steering radius this vehicle is capable of when traveling in an arc.
 Move getMovement()
          Returns the move made since the move started, but before it has completed.
 float getMovementIncrement()
           
 double getRotateMaxSpeed()
          returns the maximum value of the rotation speed;
 double getRotateSpeed()
          Returns the value of the rotation speed
 double getTravelSpeed()
          Returns the speed at which the robot will travel forward and backward (and to some extent arcs, although actual arc speed is slightly less).
 boolean isMoving()
          true if the robot is moving
 boolean isStalled()
           
protected  void movementStart(boolean alert)
          called at start of a movement to inform the listeners that a movement has started
 void quickStop()
          Stops the robot almost immediately.
 void reset()
          Resets tacho count for both motors.
 void rotate(double angle)
          Rotates the NXT robot through a specific angle.
 void rotate(double angle, boolean immediateReturn)
          Rotates the NXT robot through a specific angle.
 void rotateLeft()
           
 void rotateRight()
           
 void rotationStarted(RegulatedMotor motor, int tachoCount, boolean stall, long ts)
          MotorListener interface method is called by RegulatedMotor when a motor rotation starts.
 void rotationStopped(RegulatedMotor motor, int tachoCount, boolean stall, long ts)
          called by RegulatedMotor when a motor rotation is complete calls movementStop() after both motors stop;
 void setAcceleration(int acceleration)
          Sets the normal acceleration of the robot in distance/second/second where distance is in the units of wheel diameter.
 void setMinRadius(double radius)
          Set the radius of the minimum turning circle.
 void setRotateSpeed(double rotateSpeed)
          sets the rotation speed of the vehicle, degrees per second
 void setTravelSpeed(double travelSpeed)
          set travel speed in wheel diameter units per second
 void steer(double turnRate)
          Starts the robot moving forward along a curved path.
 void steer(double turnRate, double angle)
          Moves the robot along a curved path through a specified turn angle.
 void steer(double turnRate, double angle, boolean immediateReturn)
          Moves the robot along a curved path for a specified angle of rotation.
 void steerBackward(double turnRate)
          Starts the robot moving backward along a curved path.
 void stop()
          Stops the NXT robot.
 void travel(double distance)
          Moves the NXT robot a specific distance in an (hopefully) straight line.
A positive distance causes forward motion, a negative distance moves backward.
 void travel(double distance, boolean immediateReturn)
          Moves the NXT robot a specific distance in an (hopefully) straight line.
A positive distance causes forward motion, a negative distance moves backward.
 void travelArc(double radius, double distance)
          Moves the NXT robot a specified distance along an arc of specified radius, after which the robot stops moving.
 void travelArc(double radius, double distance, boolean immediateReturn)
          Moves the NXT robot a specified distance along an arc of specified radius, after which the robot stops moving.
 
Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
 

Field Detail

_left

protected final RegulatedMotor _left
Left motor..


_right

protected final RegulatedMotor _right
Right motor.


_outside

protected RegulatedMotor _outside
The motor at the outside of the turn. set by steer(turnRate) used by other steer methodsl


_leftDegPerDistance

protected final float _leftDegPerDistance
Left motor degrees per unit of travel.


_rightDegPerDistance

protected final float _rightDegPerDistance
Right motor degrees per unit of travel.


_type

protected Move.MoveType _type
Constructor Detail

DifferentialPilot

public DifferentialPilot(double wheelDiameter,
                         double trackWidth,
                         RegulatedMotor leftMotor,
                         RegulatedMotor rightMotor)
Allocates a DifferentialPilot object, and sets the physical parameters of the NXT robot.
Assumes Motor.forward() causes the robot to move forward.

Parameters:
wheelDiameter - Diameter of the tire, in any convenient units (diameter in mm is usually printed on the tire).
trackWidth - Distance between center of right tire and center of left tire, in same units as wheelDiameter.
leftMotor - The left Motor (e.g., Motor.C).
rightMotor - The right Motor (e.g., Motor.A).

DifferentialPilot

public DifferentialPilot(double wheelDiameter,
                         double trackWidth,
                         RegulatedMotor leftMotor,
                         RegulatedMotor rightMotor,
                         boolean reverse)
Allocates a DifferentialPilot object, and sets the physical parameters of the NXT robot.

Parameters:
wheelDiameter - Diameter of the tire, in any convenient units (diameter in mm is usually printed on the tire).
trackWidth - Distance between center of right tire and center of left tire, in same units as wheelDiameter.
leftMotor - The left Motor (e.g., Motor.C).
rightMotor - The right Motor (e.g., Motor.A).
reverse - If true, the NXT robot moves forward when the motors are running backward.

DifferentialPilot

public DifferentialPilot(double leftWheelDiameter,
                         double rightWheelDiameter,
                         double trackWidth,
                         RegulatedMotor leftMotor,
                         RegulatedMotor rightMotor,
                         boolean reverse)
Allocates a DifferentialPilot object, and sets the physical parameters of the NXT robot.

Parameters:
leftWheelDiameter - Diameter of the left wheel, in any convenient units (diameter in mm is usually printed on the tire).
rightWheelDiameter - Diameter of the right wheel. You can actually fit intentionally wheels with different size to your robot. If you fitted wheels with the same size, but your robot is not going straight, try swapping the wheels and see if it deviates into the other direction. That would indicate a small difference in wheel size. Adjust wheel size accordingly. The minimum change in wheel size which will actually have an effect is given by minChange = A*wheelDiameter*wheelDiameter/(1-(A*wheelDiameter) where A = PI/(moveSpeed*360). Thus for a moveSpeed of 25 cm/second and a wheelDiameter of 5,5 cm the minChange is about 0,01058 cm. The reason for this is, that different while sizes will result in different motor speed. And that is given as an integer in degree per second.
trackWidth - Distance between center of right tire and center of left tire, in same units as wheelDiameter.
leftMotor - The left Motor (e.g., Motor.C).
rightMotor - The right Motor (e.g., Motor.A).
reverse - If true, the NXT robot moves forward when the motors are running backward.
Method Detail

setTravelSpeed

public void setTravelSpeed(double travelSpeed)
set travel speed in wheel diameter units per second

Specified by:
setTravelSpeed in interface MoveController
Parameters:
travelSpeed - : speed in distance (wheel diameter)units/sec

getTravelSpeed

public double getTravelSpeed()
Description copied from interface: MoveController
Returns the speed at which the robot will travel forward and backward (and to some extent arcs, although actual arc speed is slightly less). Speed is measured in units/second. e.g. If wheel diameter is cm, then speed is cm/sec.

Specified by:
getTravelSpeed in interface MoveController
Returns:
Speed in chosen units per second (e.g. cm/sec)

setAcceleration

public void setAcceleration(int acceleration)
Sets the normal acceleration of the robot in distance/second/second where distance is in the units of wheel diameter. The default value is 4 times the maximum travel speed.

Parameters:
acceleration -

getMaxTravelSpeed

public double getMaxTravelSpeed()
Description copied from interface: MoveController
Returns the maximum speed at which this robot is capable of traveling forward and backward. Speed is measured in units/second. e.g. If wheel diameter is cm, then speed is cm/sec.

Specified by:
getMaxTravelSpeed in interface MoveController
Returns:
Speed in chosen units per second (e.g. cm/sec)

setRotateSpeed

public void setRotateSpeed(double rotateSpeed)
sets the rotation speed of the vehicle, degrees per second

Specified by:
setRotateSpeed in interface RotateMoveController
Parameters:
rotateSpeed -

getRotateSpeed

public double getRotateSpeed()
Description copied from interface: RotateMoveController
Returns the value of the rotation speed

Specified by:
getRotateSpeed in interface RotateMoveController
Returns:
the rotate speed in degrees per second

getMaxRotateSpeed

public float getMaxRotateSpeed()

getRotateMaxSpeed

public double getRotateMaxSpeed()
Description copied from interface: RotateMoveController
returns the maximum value of the rotation speed;

Specified by:
getRotateMaxSpeed in interface RotateMoveController
Returns:
max rotation speed

forward

public void forward()
Starts the NXT robot moving forward.

Specified by:
forward in interface MoveController

backward

public void backward()
Starts the NXT robot moving backward.

Specified by:
backward in interface MoveController

rotateLeft

public void rotateLeft()

rotateRight

public void rotateRight()

rotate

public void rotate(double angle)
Rotates the NXT robot through a specific angle. Returns when angle is reached. Wheels turn in opposite directions producing a zero radius turn.
Note: Requires correct values for wheel diameter and track width. calls rotate(angle,false)

Specified by:
rotate in interface RotateMoveController
Parameters:
angle - The wanted angle of rotation in degrees. Positive angle rotate left (anti-clockwise), negative right.

rotate

public void rotate(double angle,
                   boolean immediateReturn)
Rotates the NXT robot through a specific angle. Returns when angle is reached. Wheels turn in opposite directions producing a zero radius turn.
Note: Requires correct values for wheel diameter and track width. Side effect: inform listeners

Specified by:
rotate in interface RotateMoveController
Parameters:
angle - The wanted angle of rotation in degrees. Positive angle rotate left (anti-clockwise), negative right.
immediateReturn - If true this method returns immediately.

stop

public void stop()
Stops the NXT robot. side effect: inform listeners of end of movement

Specified by:
stop in interface MoveController

quickStop

public void quickStop()
Stops the robot almost immediately. Use this method if the normal stop() is too slow;


travel

public void travel(double distance)
Moves the NXT robot a specific distance in an (hopefully) straight line.
A positive distance causes forward motion, a negative distance moves backward. If a drift correction has been specified in the constructor it will be applied to the left motor. calls travel(distance, false)

Specified by:
travel in interface MoveController
Parameters:
distance - The distance to move. Unit of measure for distance must be same as wheelDiameter and trackWidth.

travel

public void travel(double distance,
                   boolean immediateReturn)
Moves the NXT robot a specific distance in an (hopefully) straight line.
A positive distance causes forward motion, a negative distance moves backward. If a drift correction has been specified in the constructor it will be applied to the left motor.

Specified by:
travel in interface MoveController
Parameters:
distance - The distance to move. Unit of measure for distance must be same as wheelDiameter and trackWidth.
immediateReturn - If true this method returns immediately.

arcForward

public void arcForward(double radius)
Description copied from interface: ArcMoveController
Starts the NXT robot moving forward along an arc with a specified radius.

If radius is positive, the robot arcs left, and the center of the turning circle is on the left side of the robot.
If radius is negative, the robot arcs right, and the center of the turning circle is on the right side of the robot.
If radius is zero, the robot rotates in place.

Postcondition: Motor speeds are unpredictable.

Note: If you have specified a drift correction in the constructor it will not be applied in this method.

Specified by:
arcForward in interface ArcMoveController
Parameters:
radius - of the arc path. If positive, the left side of the robot is on the inside of the turn. If negative, the left side of the robot is on the outside of the turn.

arcBackward

public void arcBackward(double radius)
Description copied from interface: ArcMoveController
Starts the NXT robot moving backward along an arc with a specified radius.

If radius is positive, the robot arcs left, and the center of the turning circle is on the left side of the robot.
If radius is negative, the robot arcs right, and the center of the turning circle is on the right side of the robot.
If radius is zero, the robot rotates in place.

Postcondition: Motor speeds are unpredictable.

Note: If you have specified a drift correction in the constructor it will not be applied in this method.

Specified by:
arcBackward in interface ArcMoveController
Parameters:
radius - of the arc path. If positive, the left side of the robot is on the inside of the turn. If negative, the left side of the robot is on the outside of the turn.

arc

public void arc(double radius,
                double angle)
Description copied from interface: ArcMoveController
Moves the NXT robot along an arc with a specified radius and angle, after which the robot stops moving. This method does not return until the robot has completed moving angle degrees along the arc.

If radius is positive, the robot arcs left, and the center of the turning circle is on the left side of the robot.
If radius is negative, the robot arcs right, and the center of the turning circle is on the right side of the robot.
If radius is zero, is zero, the robot rotates in place.

Robot will stop when the degrees it has moved along the arc equals angle.
If angle is positive, the robot will move travel forwards.
If angle is negative, the robot will move travel backwards. If angle is zero, the robot will not move and the method returns immediately.

Postcondition: Motor speeds are unpredictable.

Note: If you have specified a drift correction in the constructor it will not be applied in this method.

Specified by:
arc in interface ArcMoveController
Parameters:
radius - of the arc path. If positive, the left side of the robot is on the inside of the turn. If negative, the left side of the robot is on the outside of the turn.
angle - The sign of the angle determines the direction of robot motion. Positive drives the robot forward, negative drives it backward.
See Also:
ArcMoveController.travelArc(double, double)

arc

public void arc(double radius,
                double angle,
                boolean immediateReturn)
Description copied from interface: ArcMoveController
Moves the NXT robot along an arc with a specified radius and angle, after which the robot stops moving. This method has the ability to return immediately by using the immediateReturn parameter.

If radius is positive, the robot arcs left, and the center of the turning circle is on the left side of the robot.
If radius is negative, the robot arcs right, and the center of the turning circle is on the right side of the robot.
If radius is zero, is zero, the robot rotates in place.

The robot will stop when the degrees it has moved along the arc equals angle.
If angle is positive, the robot will move travel forwards.
If angle is negative, the robot will move travel backwards. If angle is zero, the robot will not move and the method returns immediately.

Postcondition: Motor speeds are unpredictable.

Note: If you have specified a drift correction in the constructor it will not be applied in this method.

Specified by:
arc in interface ArcMoveController
Parameters:
radius - of the arc path. If positive, the left side of the robot is on the inside of the turn. If negative, the left side of the robot is on the outside of the turn.
angle - The sign of the angle determines the direction of robot motion. Positive drives the robot forward, negative drives it backward.
immediateReturn - If immediateReturn is true then the method returns immediately.
See Also:
ArcMoveController.travelArc(double, double, boolean)

travelArc

public void travelArc(double radius,
                      double distance)
Description copied from interface: ArcMoveController
Moves the NXT robot a specified distance along an arc of specified radius, after which the robot stops moving. This method does not return until the robot has completed moving distance along the arc. The units (inches, cm) for distance must be the same as the units used for radius.

If radius is positive, the robot arcs left, and the center of the turning circle is on the left side of the robot.
If radius is negative, the robot arcs right, and the center of the turning circle is on the right side of the robot.
If radius is zero, the robot rotates in place

The robot will stop when it has moved along the arc distance units.
If distance is positive, the robot will move travel forwards.
If distance is negative, the robot will move travel backwards.
If distance is zero, the robot will not move and the method returns immediately.

Postcondition: Motor speeds are unpredictable.

Specified by:
travelArc in interface ArcMoveController
Parameters:
radius - of the arc path. If positive, the left side of the robot is on the inside of the turn. If negative, the left side of the robot is on the outside of the turn.
distance - to travel, in same units as radius. The sign of the distance determines the direction of robot motion. Positive drives the robot forward, negative drives it backward.
See Also:
ArcMoveController.arc(double, double)

travelArc

public void travelArc(double radius,
                      double distance,
                      boolean immediateReturn)
Description copied from interface: ArcMoveController
Moves the NXT robot a specified distance along an arc of specified radius, after which the robot stops moving. This method has the ability to return immediately by using the immediateReturn parameter. The units (inches, cm) for distance should be the same as the units used for radius.

If radius is positive, the robot arcs left, and the center of the turning circle is on the left side of the robot.
If radius is negative, the robot arcs right, and the center of the turning circle is on the right side of the robot.
If radius is zero, the robot rotates in place.

The robot will stop when it has moved along the arc distance units.
If distance is positive, the robot will move travel forwards.
If distance is negative, the robot will move travel backwards.
If distance is zero, the robot will not move and the method returns immediately.

Postcondition: Motor speeds are unpredictable.

Specified by:
travelArc in interface ArcMoveController
Parameters:
radius - of the arc path. If positive, the left side of the robot is on the inside of the turn. If negative, the left side of the robot is on the outside of the turn.
distance - to travel, in same units as radius. The sign of the distance determines the direction of robot motion. Positive drives the robot forward, negative drives it backward.
immediateReturn - If immediateReturn is true then the method returns immediately.
See Also:
ArcMoveController.arc(double, double, boolean)

steer

public void steer(double turnRate)
Starts the robot moving forward along a curved path. This method is similar to the arcForward(double radius ) method except it uses the turnRate parameter do determine the curvature of the path and therefore has the ability to drive straight. This makes it useful for line following applications.

The turnRate specifies the sharpness of the turn. Use values between -200 and +200.
A positive value means that center of the turn is on the left. If the robot is traveling toward the top of the page the arc looks like this: ).
A negative value means that center of the turn is on the right so the arc looks this: (.
. In this class, this parameter determines the ratio of inner wheel speed to outer wheel speed as a percent.
Formula: ratio = 100 - abs(turnRate).
When the ratio is negative, the outer and inner wheels rotate in opposite directions. Examples of how the formula works:

Note: If you have specified a drift correction in the constructor it will not be applied in this method.

Parameters:
turnRate - If positive, the left side of the robot is on the inside of the turn. If negative, the left side is on the outside.

steerBackward

public void steerBackward(double turnRate)
Starts the robot moving backward along a curved path. This method is essentially the same as steer(double) except that the robot moves backward instead of forward.

Parameters:
turnRate -

steer

public void steer(double turnRate,
                  double angle)
Moves the robot along a curved path through a specified turn angle. This method is similar to the arc(double radius , double angle) method except it uses a ratio of motor speeds to determine the curvature of the path and therefore has the ability to drive straight. This makes it useful for line following applications. This method does not return until the robot has completed moving angle degrees along the arc.
The turnRate specifies the sharpness of the turn. Use values between -200 and +200.
For details about how this parameter works.See steer(double turnRate)

The robot will stop when its heading has changed by the amount of the angle parameter.
If angle is positive, the robot will move in the direction that increases its heading (it turns left).
If angle is negative, the robot will move in the directin that decreases its heading (turns right).
If angle is zero, the robot will not move and the method returns immediately.

The sign of the turn rate and the sign of the angle together determine if the robot will move forward or backward. Assuming the robot is heading toward the top of the page. Then a positive turn rate means the arc looks like this: ) . If the angle is positive, the robot moves forward to increase its heading angle. If negative, it moves backward to decrease the heading.
But if the turn rate is negative, the arc looks like this: ( .So a positive angle (increase in heading) means the robot moves backwards, while a negative angle means the robot moves forward to decrease its heading.

Note: If you have specified a drift correction in the constructor it will not be applied in this method.

Parameters:
turnRate - If positive, the left side of the robot is on the inside of the turn. If negative, the left side is on the outside.
angle - The angle through which the robot will rotate. If negative, the robot will move in the directin that decreases its heading.

steer

public void steer(double turnRate,
                  double angle,
                  boolean immediateReturn)
Moves the robot along a curved path for a specified angle of rotation. This method is similar to the arc(double radius, double angle, boolean immediateReturn) method except it uses the turnRate() parameter to determine the curvature of the path and therefore has the ability to drive straight. This makes it useful for line following applications. This method has the ability to return immediately by using the immediateReturn parameter set to true.

The turnRate specifies the sharpness of the turn. Use values between -200 and +200.
For details about how this parameter works, see steer(double turnRate)

The robot will stop when its heading has changed by the amount of the angle parameter.
If angle is positive, the robot will move in the direction that increases its heading (it turns left).
If angle is negative, the robot will move in the direction that decreases its heading (turns right).
If angle is zero, the robot will not move and the method returns immediately.
For more details about this parameter, see steer(double turnRate, double angle)

Note: If you have specified a drift correction in the constructor it will not be applied in this method.

Parameters:
turnRate - If positive, the left side of the robot is on the inside of the turn. If negative, the left side is on the outside.
angle - The angle through which the robot will rotate. If negative, robot traces the turning circle backwards.
immediateReturn - If immediateReturn is true then the method returns immediately.

rotationStopped

public void rotationStopped(RegulatedMotor motor,
                            int tachoCount,
                            boolean stall,
                            long ts)
called by RegulatedMotor when a motor rotation is complete calls movementStop() after both motors stop;

Specified by:
rotationStopped in interface RegulatedMotorListener
Parameters:
motor -
tachoCount -
stall - : true if motor is sealled
ts - s time stamp

rotationStarted

public void rotationStarted(RegulatedMotor motor,
                            int tachoCount,
                            boolean stall,
                            long ts)
MotorListener interface method is called by RegulatedMotor when a motor rotation starts.

Specified by:
rotationStarted in interface RegulatedMotorListener
Parameters:
motor -
tachoCount -
stall - true of the motor is stalled
ts - time stamp

movementStart

protected void movementStart(boolean alert)
called at start of a movement to inform the listeners that a movement has started


isMoving

public boolean isMoving()
Description copied from interface: MoveController
true if the robot is moving

Specified by:
isMoving in interface MoveController
Returns:
true if the NXT robot is moving.

isStalled

public boolean isStalled()

reset

public void reset()
Resets tacho count for both motors.


setMinRadius

public void setMinRadius(double radius)
Set the radius of the minimum turning circle. Note: A DifferentialPilot robot can simulate a SteeringPilot robot by calling DifferentialPilot.setMinRadius() and setting the value to something greater than zero (example: 15 cm).

Specified by:
setMinRadius in interface ArcMoveController
Parameters:
radius - in degrees

getMinRadius

public double getMinRadius()
Description copied from interface: ArcMoveController
The minimum steering radius this vehicle is capable of when traveling in an arc. Theoretically this should be identical for both forward and reverse travel. In practice?

Specified by:
getMinRadius in interface ArcMoveController
Returns:
the radius in degrees

getMovementIncrement

public float getMovementIncrement()
Returns:
The move distance since it last started moving

getAngleIncrement

public float getAngleIncrement()
Returns:
The angle rotated since rotation began.

addMoveListener

public void addMoveListener(MoveListener m)
Description copied from interface: MoveProvider
Adds a MoveListener that will be notified of all movement events.

Specified by:
addMoveListener in interface MoveProvider
Parameters:
m - the move listener

getMovement

public Move getMovement()
Description copied from interface: MoveProvider
Returns the move made since the move started, but before it has completed. This method is used by GUI maps to display the movement of a robot in real time. The robot must be capable of determining the move while it is in motion.

Specified by:
getMovement in interface MoveProvider
Returns:
The move made since the move started.