WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
wpi::Field2d Class Reference

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

#include <wpi/smartdashboard/Field2d.hpp>

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

Public Types

using Entry = size_t

Public Member Functions

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

Additional Inherited Members

Protected Member Functions inherited from wpi::util::SendableHelper< Field2d >
constexpr ~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 wpi::Field2d::Entry = size_t

Constructor & Destructor Documentation

◆ Field2d() [1/2]

wpi::Field2d::Field2d ( )

◆ Field2d() [2/2]

wpi::Field2d::Field2d ( Field2d && rhs)

Member Function Documentation

◆ GetObject()

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

Get or create a field object.

Returns
Field object

◆ GetRobotObject()

FieldObject2d * wpi::Field2d::GetRobotObject ( )

Get the robot object.

Returns
Field object for robot

◆ GetRobotPose()

wpi::math::Pose2d wpi::Field2d::GetRobotPose ( ) const

Get the robot pose.

Returns
2D pose

◆ InitSendable()

void wpi::Field2d::InitSendable ( wpi::nt::NTSendableBuilder & builder)
overridevirtual

Initializes this Sendable object.

Parameters
buildersendable builder

Implements wpi::nt::NTSendable.

◆ operator=()

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

◆ SetRobotPose() [1/2]

void wpi::Field2d::SetRobotPose ( const wpi::math::Pose2d & pose)

Set the robot pose from a Pose object.

Parameters
pose2D pose

◆ SetRobotPose() [2/2]

void wpi::Field2d::SetRobotPose ( wpi::units::meter_t x,
wpi::units::meter_t y,
wpi::math::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: