Game field object on a Field2d.
More...
#include <frc/smartdashboard/FieldObject2d.h>
Game field object on a Field2d.
◆ FieldObject2d() [1/2]
frc::FieldObject2d::FieldObject2d |
( |
std::string_view |
name, |
|
|
const private_init & |
|
|
) |
| |
|
inline |
◆ FieldObject2d() [2/2]
◆ 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
-
- Returns
- vector of 2D poses
◆ GetPoses() [2/2]
Get multiple poses.
- Parameters
-
out | output SmallVector to hold 2D poses |
- Returns
- span referring to output SmallVector
◆ operator=()
◆ SetPose() [1/2]
void frc::FieldObject2d::SetPose |
( |
const Pose2d & |
pose | ) |
|
Set the pose from a Pose object.
- Parameters
-
◆ 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
-
x | X location |
y | Y location |
rotation | rotation |
◆ 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
-
◆ 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
-
◆ SetTrajectory()
void frc::FieldObject2d::SetTrajectory |
( |
const Trajectory & |
trajectory | ) |
|
Sets poses from a trajectory.
- Parameters
-
trajectory | The trajectory from which poses should be added. |
◆ Field2d
The documentation for this class was generated from the following file: