Class Field2d

  • All Implemented Interfaces:
    NTSendable, Sendable

    public class Field2d
    extends Object
    implements NTSendable
    2D representation of game field for dashboards.

    An object's pose is the location shown on the dashboard view. Note that for the robot, this may or may not match the internal odometry. For example, 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 wheel odometry), and set the new pose.

    This class provides methods to set the robot pose, but other objects can also be shown by using the getObject() function. Other objects can also have multiple poses (which will show the object at multiple locations).

    • Constructor Detail

      • Field2d

        public Field2d()
        Constructor.
    • 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 meters
        yMeters - Y location, in meters
        rotation - rotation
      • getObject

        public FieldObject2d getObject​(String name)
        Get or create a field object.
        Parameters:
        name - The field object's name.
        Returns:
        Field object