Class Field2d
- java.lang.Object
-
- Field2d
-
public class Field2d extends Object
2D representation of game field (for simulation).In non-simulation mode this simply stores and returns the robot pose.
The robot pose is the actual location shown on the simulation view. This may or may not match the robot's internal odometry. For example, if the robot is shown at a particular starting location, the pose in this class would represent the actual location on the field, but the robot's internal state might have a 0,0,0 pose (unless it's initialized to something different).
As the user is able to edit the pose, code performing updates should get the robot pose, transform it as appropriate (e.g. based on simulated wheel velocity), and set the new pose.
-
-
Constructor Summary
Constructors Constructor Description Field2d()
-
Method Summary
All Methods Instance Methods Concrete Methods Modifier and Type Method Description Pose2dgetRobotPose()Get the robot pose.voidsetRobotPose(double xMeters, double yMeters, Rotation2d rotation)Set the robot pose from x, y, and rotation.voidsetRobotPose(Pose2d pose)Set the robot pose from a Pose object.
-
-
-
Method Detail
-
setRobotPose
public void setRobotPose(Pose2d pose)
Set the robot pose from a Pose object.- Parameters:
pose- 2D pose
-
setRobotPose
public void setRobotPose(double xMeters, double yMeters, Rotation2d rotation)Set the robot pose from x, y, and rotation.- Parameters:
xMeters- X location, in metersyMeters- Y location, in metersrotation- rotation
-
getRobotPose
public Pose2d getRobotPose()
Get the robot pose.- Returns:
- 2D pose
-
-