Interface LineFollowingMoveController
-
- All Superinterfaces:
ArcMoveController,ArcRotateMoveController,MoveController,MoveProvider,RotateMoveController
- All Known Implementing Classes:
CompassPilot,DifferentialPilot
public interface LineFollowingMoveController extends ArcRotateMoveController
-
-
Field Summary
-
Fields inherited from interface lejos.robotics.navigation.MoveController
WHEEL_SIZE_EV3, WHEEL_SIZE_NXT1, WHEEL_SIZE_NXT2, WHEEL_SIZE_RCX
-
-
Method Summary
All Methods Instance Methods Abstract Methods Modifier and Type Method Description voidsteer(double turnRate)Moves the robot forward while making a curve specified byturnRate.voidsteerBackward(double steerRatio)Moves the robot backward while making a curve specified byturnRate.-
Methods inherited from interface lejos.robotics.navigation.ArcMoveController
arc, arc, arcBackward, arcForward, getMinRadius, setMinRadius, travelArc, travelArc
-
Methods inherited from interface lejos.robotics.navigation.MoveController
backward, forward, getLinearAcceleration, getLinearSpeed, getMaxLinearSpeed, isMoving, setLinearAcceleration, setLinearSpeed, stop, travel, travel
-
Methods inherited from interface lejos.robotics.navigation.MoveProvider
addMoveListener, getMovement
-
Methods inherited from interface lejos.robotics.navigation.RotateMoveController
getAngularAcceleration, getAngularSpeed, getMaxAngularSpeed, rotate, rotate, rotateLeft, rotateRight, setAngularAcceleration, setAngularSpeed
-
-
-
-
Method Detail
-
steer
void steer(double turnRate)
Moves the robot forward while making a curve specified byturnRate.This move is suited for line following as it executes immediately without stopping the move that the robot is currently executing. It is also non blocking, control goes back to the main program right way.
The
turnRatespecifies 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:steer(0)-> inner and outer wheels turn at the same speed, travel straightsteer(25)-> the inner wheel turns at 75% of the speed of the outer wheel, turn leftsteer(100)-> the inner wheel stops and the outer wheel is at 100 percent, turn leftsteer(200)-> the inner wheel turns at the same speed as the outer wheel - a zero radius turn.
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
void steerBackward(double steerRatio)
Moves the robot backward while making a curve specified byturnRate.This move is suited for line following as it executes immediately without stopping the move that the robot is currently executing. It is also non blocking, control goes back to the main program right way.
The
turnRatespecifies 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:steer(0)-> inner and outer wheels turn at the same speed, travel straightsteer(25)-> the inner wheel turns at 75% of the speed of the outer wheel, turn leftsteer(100)-> the inner wheel stops and the outer wheel is at 100 percent, turn leftsteer(200)-> the inner wheel turns at the same speed as the outer wheel - a zero radius turn.
Note: If you have specified a drift correction in the constructor it will not be applied in this method.
- Parameters:
steerRatio- If positive, the left side of the robot is on the inside of the turn. If negative, the left side is on the outside.
-
-