Class FieldObject2d
java.lang.Object
edu.wpi.first.wpilibj.smartdashboard.FieldObject2d
- All Implemented Interfaces:
AutoCloseable
Game field object on a Field2d.
-
Method Summary
Modifier and TypeMethodDescriptionvoidclose()getPose()Get the pose.getPoses()Get multiple poses.voidsetPose(double xMeters, double yMeters, Rotation2d rotation) Set the pose from x, y, and rotation.voidSet the pose from a Pose object.voidSet multiple poses from a list of Pose objects.voidSet multiple poses from a list of Pose objects.voidsetTrajectory(Trajectory trajectory) Sets poses from a trajectory.
-
Method Details
-
close
- Specified by:
closein interfaceAutoCloseable
-
setPose
Set the pose from a Pose object.- Parameters:
pose- 2D pose
-
setPose
Set the pose from x, y, and rotation.- Parameters:
xMeters- X location, in metersyMeters- Y location, in metersrotation- rotation
-
getPose
Get the pose.- Returns:
- 2D pose
-
setPoses
Set multiple poses from a list of Pose objects. The total number of poses is limited to 85.- Parameters:
poses- list of 2D poses
-
setPoses
Set multiple poses from a list of Pose objects. The total number of poses is limited to 85.- Parameters:
poses- list of 2D poses
-
setTrajectory
Sets poses from a trajectory.- Parameters:
trajectory- The trajectory from which the poses should be added.
-
getPoses
Get multiple poses.- Returns:
- list of 2D poses
-