Class Field2d
- java.lang.Object
-
- edu.wpi.first.wpilibj.smartdashboard.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 Summary
Constructors Constructor Description Field2d()
Constructor.
-
Method Summary
All Methods Instance Methods Concrete Methods Modifier and Type Method Description FieldObject2d
getObject(String name)
Get or create a field object.FieldObject2d
getRobotObject()
Get the robot object.Pose2d
getRobotPose()
Get the robot pose.void
initSendable(NTSendableBuilder builder)
Initializes thisSendable
object.void
setRobotPose(double xMeters, double yMeters, Rotation2d rotation)
Set the robot pose from x, y, and rotation.void
setRobotPose(Pose2d pose)
Set the robot pose from a Pose object.-
Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
-
Methods inherited from interface edu.wpi.first.networktables.NTSendable
initSendable
-
-
-
-
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 metersyMeters
- Y location, in metersrotation
- rotation
-
getRobotPose
public Pose2d getRobotPose()
Get the robot pose.- Returns:
- 2D pose
-
getObject
public FieldObject2d getObject(String name)
Get or create a field object.- Parameters:
name
- The field object's name.- Returns:
- Field object
-
getRobotObject
public FieldObject2d getRobotObject()
Get the robot object.- Returns:
- Field object for robot
-
initSendable
public void initSendable(NTSendableBuilder builder)
Description copied from interface:NTSendable
Initializes thisSendable
object.- Specified by:
initSendable
in interfaceNTSendable
- Parameters:
builder
- sendable builder
-
-