WPILibC++ 2024.3.2
frc::Field2d Class Reference

2D representation of game field for dashboards. More...

#include <frc/smartdashboard/Field2d.h>

Inheritance diagram for frc::Field2d:
nt::NTSendable wpi::SendableHelper< Field2d > wpi::Sendable

Public Types

using Entry = size_t
 

Public Member Functions

 Field2d ()
 
 Field2d (Field2d &&rhs)
 
Field2doperator= (Field2d &&rhs)
 
void SetRobotPose (const Pose2d &pose)
 Set the robot pose from a Pose object. More...
 
void SetRobotPose (units::meter_t x, units::meter_t y, Rotation2d rotation)
 Set the robot pose from x, y, and rotation. More...
 
Pose2d GetRobotPose () const
 Get the robot pose. More...
 
FieldObject2dGetObject (std::string_view name)
 Get or create a field object. More...
 
FieldObject2dGetRobotObject ()
 Get the robot object. More...
 
void InitSendable (nt::NTSendableBuilder &builder) override
 Initializes this Sendable object. More...
 
- Public Member Functions inherited from nt::NTSendable
virtual void InitSendable (NTSendableBuilder &builder)=0
 Initializes this Sendable object. More...
 
void InitSendable (wpi::SendableBuilder &builder) override
 Initializes this Sendable object. More...
 
- Public Member Functions inherited from wpi::Sendable
virtual ~Sendable ()=default
 
virtual void InitSendable (SendableBuilder &builder)=0
 Initializes this Sendable object. More...
 
- Public Member Functions inherited from wpi::SendableHelper< Field2d >
 SendableHelper (const SendableHelper &rhs)=default
 
 SendableHelper (SendableHelper &&rhs)
 
SendableHelperoperator= (const SendableHelper &rhs)=default
 
SendableHelperoperator= (SendableHelper &&rhs)
 

Additional Inherited Members

- Protected Member Functions inherited from wpi::SendableHelper< Field2d >
 SendableHelper ()=default
 
 ~SendableHelper ()
 

Detailed Description

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, 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 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).

Member Typedef Documentation

◆ Entry

using frc::Field2d::Entry = size_t

Constructor & Destructor Documentation

◆ Field2d() [1/2]

frc::Field2d::Field2d ( )

◆ Field2d() [2/2]

frc::Field2d::Field2d ( Field2d &&  rhs)

Member Function Documentation

◆ GetObject()

FieldObject2d * frc::Field2d::GetObject ( std::string_view  name)

Get or create a field object.

Returns
Field object

◆ GetRobotObject()

FieldObject2d * frc::Field2d::GetRobotObject ( )

Get the robot object.

Returns
Field object for robot

◆ GetRobotPose()

Pose2d frc::Field2d::GetRobotPose ( ) const

Get the robot pose.

Returns
2D pose

◆ InitSendable()

void frc::Field2d::InitSendable ( nt::NTSendableBuilder builder)
overridevirtual

Initializes this Sendable object.

Parameters
buildersendable builder

Implements nt::NTSendable.

◆ operator=()

Field2d & frc::Field2d::operator= ( Field2d &&  rhs)

◆ SetRobotPose() [1/2]

void frc::Field2d::SetRobotPose ( const Pose2d pose)

Set the robot pose from a Pose object.

Parameters
pose2D pose

◆ SetRobotPose() [2/2]

void frc::Field2d::SetRobotPose ( units::meter_t  x,
units::meter_t  y,
Rotation2d  rotation 
)

Set the robot pose from x, y, and rotation.

Parameters
xX location
yY location
rotationrotation

The documentation for this class was generated from the following file: