7#include <initializer_list>
31 struct private_init {};
34 FieldObject2d(std::string_view name,
const private_init&) : m_name{name} {}
76 void SetPoses(std::initializer_list<Pose2d> poses);
101 void UpdateEntry(
bool setDefault =
false);
102 void UpdateFromEntry()
const;
This file defines the SmallVector class.
2D representation of game field for dashboards.
Definition Field2d.h:42
Game field object on a Field2d.
Definition FieldObject2d.h:29
void SetTrajectory(const Trajectory &trajectory)
Sets poses from a trajectory.
std::span< const Pose2d > GetPoses(wpi::SmallVectorImpl< Pose2d > &out) const
Get multiple poses.
FieldObject2d(FieldObject2d &&rhs)
void SetPose(const Pose2d &pose)
Set the pose from a Pose object.
std::vector< Pose2d > GetPoses() const
Get multiple poses.
void SetPose(units::meter_t x, units::meter_t y, Rotation2d rotation)
Set the pose from x, y, and rotation.
FieldObject2d & operator=(FieldObject2d &&rhs)
void SetPoses(std::initializer_list< Pose2d > poses)
Set multiple poses from an array of Pose objects.
void SetPoses(std::span< const Pose2d > poses)
Set multiple poses from an array of Pose objects.
FieldObject2d(std::string_view name, const private_init &)
Definition FieldObject2d.h:34
Pose2d GetPose() const
Get the pose.
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.h:28
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.h:31
Represents a time-parameterized trajectory.
Definition Trajectory.h:29
NetworkTables DoubleArray entry.
Definition DoubleArrayTopic.h:238
This is a 'vector' (really, a variable-sized array), optimized for the case when the array is small.
Definition SmallVector.h:1212
This class consists of common code factored out of the SmallVector class to reduce code duplication b...
Definition sha1.h:30
::std::mutex mutex
Definition mutex.h:17