Package dev.narlyx.tweetybird
Class TweetyBird
java.lang.Object
dev.narlyx.tweetybird.TweetyBird
This is the main class behind TweetyBird, use this class to setup, start, and use TweetyBird.
-
Nested Class Summary
Nested ClassesModifier and TypeClassDescriptionstatic classUse this method to properly set up TweetyBird using Java's builder pattern.static interfaceAn interface for TweetyBird to define the structure of a driver class used to control movement.static interfaceAn interface for TweetyBird to define the structure of a odometer class used to receive data on the robot's current position. -
Field Summary
FieldsModifier and TypeFieldDescriptionprotected final doubleprotected final booleanprotected final doubleprotected final TweetyBird.Driverprotected final doubleprotected final doubleprotected final TweetyBird.Odometerprotected final com.qualcomm.robotcore.eventloop.opmode.LinearOpModeprotected final doubleprotected final Runtimeprotected final doubleprotected final WaypointQueue -
Constructor Summary
ConstructorsConstructorDescriptionTweetyBird(TweetyBird.Builder builder) Do NOT call this method yourself, instead use the builder to start TweetyBird -
Method Summary
Modifier and TypeMethodDescriptionvoidclose()Terminates TweetyBirdbooleanisBusy()Returns weather the mover is currently in progress or notvoidresetPosition(double x, double y, double z) Shortcut to reset the position in the provided odometerprotected voidsendDebugMessage(String message) Internal method used to send debug messagesvoidsendTargetPosition(double x, double y, double z) Creates a new waypoint and adds it to the end of the queuevoidWill wait in a while loop until isBusy() is false
-
Field Details
-
opMode
protected final com.qualcomm.robotcore.eventloop.opmode.LinearOpMode opMode -
odometer
-
driver
-
waypointQueue
-
minSpeed
protected final double minSpeed -
maxSpeed
protected final double maxSpeed -
distanceBuffer
protected final double distanceBuffer -
rotationBuffer
protected final double rotationBuffer -
speedModifier
protected final double speedModifier -
correctionOverpower
protected final double correctionOverpower -
debuggingEnabled
protected final boolean debuggingEnabled -
runtime
-
-
Constructor Details
-
TweetyBird
Do NOT call this method yourself, instead use the builder to start TweetyBird- Parameters:
builder- Passed builder
-
-
Method Details
-
sendTargetPosition
public void sendTargetPosition(double x, double y, double z) Creates a new waypoint and adds it to the end of the queue- Parameters:
x- New target Xy- New target Yz- New target Z
-
resetPosition
public void resetPosition(double x, double y, double z) Shortcut to reset the position in the provided odometer- Parameters:
x- New xy- New yz- New z
-
isBusy
public boolean isBusy()Returns weather the mover is currently in progress or not- Returns:
- Busy
-
waitWhileBusy
public void waitWhileBusy()Will wait in a while loop until isBusy() is false -
close
public void close()Terminates TweetyBird -
sendDebugMessage
Internal method used to send debug messages- Parameters:
message- message to be sent
-