WPILibC++ 2024.3.2
frc::FieldObject2d Class Reference

Game field object on a Field2d. More...

#include <frc/smartdashboard/FieldObject2d.h>

Public Member Functions

 FieldObject2d (std::string_view name, const private_init &)
 
 FieldObject2d (FieldObject2d &&rhs)
 
FieldObject2doperator= (FieldObject2d &&rhs)
 
void SetPose (const Pose2d &pose)
 Set the pose from a Pose object. More...
 
void SetPose (units::meter_t x, units::meter_t y, Rotation2d rotation)
 Set the pose from x, y, and rotation. More...
 
Pose2d GetPose () const
 Get the pose. More...
 
void SetPoses (std::span< const Pose2d > poses)
 Set multiple poses from an array of Pose objects. More...
 
void SetPoses (std::initializer_list< Pose2d > poses)
 Set multiple poses from an array of Pose objects. More...
 
void SetTrajectory (const Trajectory &trajectory)
 Sets poses from a trajectory. More...
 
std::vector< Pose2dGetPoses () const
 Get multiple poses. More...
 
std::span< const Pose2dGetPoses (wpi::SmallVectorImpl< Pose2d > &out) const
 Get multiple poses. More...
 

Friends

class Field2d
 

Detailed Description

Game field object on a Field2d.

Constructor & Destructor Documentation

◆ FieldObject2d() [1/2]

frc::FieldObject2d::FieldObject2d ( std::string_view  name,
const private_init &   
)
inline

◆ FieldObject2d() [2/2]

frc::FieldObject2d::FieldObject2d ( FieldObject2d &&  rhs)

Member Function Documentation

◆ GetPose()

Pose2d frc::FieldObject2d::GetPose ( ) const

Get the pose.

Returns
2D pose, or 0,0,0 if unknown / does not exist

◆ GetPoses() [1/2]

std::vector< Pose2d > frc::FieldObject2d::GetPoses ( ) const

Get multiple poses.

Parameters
objObject entry
Returns
vector of 2D poses

◆ GetPoses() [2/2]

std::span< const Pose2d > frc::FieldObject2d::GetPoses ( wpi::SmallVectorImpl< Pose2d > &  out) const

Get multiple poses.

Parameters
outoutput SmallVector to hold 2D poses
Returns
span referring to output SmallVector

◆ operator=()

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

◆ SetPose() [1/2]

void frc::FieldObject2d::SetPose ( const Pose2d pose)

Set the pose from a Pose object.

Parameters
pose2D pose

◆ SetPose() [2/2]

void frc::FieldObject2d::SetPose ( units::meter_t  x,
units::meter_t  y,
Rotation2d  rotation 
)

Set the pose from x, y, and rotation.

Parameters
xX location
yY location
rotationrotation

◆ SetPoses() [1/2]

void frc::FieldObject2d::SetPoses ( std::initializer_list< Pose2d poses)

Set multiple poses from an array of Pose objects.

The total number of poses is limited to 85.

Parameters
posesarray of 2D poses

◆ SetPoses() [2/2]

void frc::FieldObject2d::SetPoses ( std::span< const Pose2d poses)

Set multiple poses from an array of Pose objects.

The total number of poses is limited to 85.

Parameters
posesarray of 2D poses

◆ SetTrajectory()

void frc::FieldObject2d::SetTrajectory ( const Trajectory trajectory)

Sets poses from a trajectory.

Parameters
trajectoryThe trajectory from which poses should be added.

Friends And Related Function Documentation

◆ Field2d

friend class Field2d
friend

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