WPILibC++ 2024.3.2
FieldObject2d.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <initializer_list>
8#include <span>
9#include <string>
10#include <string_view>
11#include <vector>
12
14#include <units/length.h>
15#include <wpi/SmallVector.h>
16#include <wpi/mutex.h>
17
18#include "frc/geometry/Pose2d.h"
20
21namespace frc {
22
23class Field2d;
24class Trajectory;
25
26/**
27 * Game field object on a Field2d.
28 */
30 friend class Field2d;
31 struct private_init {};
32
33 public:
34 FieldObject2d(std::string_view name, const private_init&) : m_name{name} {}
35
38
39 /**
40 * Set the pose from a Pose object.
41 *
42 * @param pose 2D pose
43 */
44 void SetPose(const Pose2d& pose);
45
46 /**
47 * Set the pose from x, y, and rotation.
48 *
49 * @param x X location
50 * @param y Y location
51 * @param rotation rotation
52 */
53 void SetPose(units::meter_t x, units::meter_t y, Rotation2d rotation);
54
55 /**
56 * Get the pose.
57 *
58 * @return 2D pose, or 0,0,0 if unknown / does not exist
59 */
60 Pose2d GetPose() const;
61
62 /**
63 * Set multiple poses from an array of Pose objects.
64 * The total number of poses is limited to 85.
65 *
66 * @param poses array of 2D poses
67 */
68 void SetPoses(std::span<const Pose2d> poses);
69
70 /**
71 * Set multiple poses from an array of Pose objects.
72 * The total number of poses is limited to 85.
73 *
74 * @param poses array of 2D poses
75 */
76 void SetPoses(std::initializer_list<Pose2d> poses);
77
78 /**
79 * Sets poses from a trajectory.
80 *
81 * @param trajectory The trajectory from which poses should be added.
82 */
83 void SetTrajectory(const Trajectory& trajectory);
84
85 /**
86 * Get multiple poses.
87 *
88 * @param obj Object entry
89 * @return vector of 2D poses
90 */
91 std::vector<Pose2d> GetPoses() const;
92
93 /**
94 * Get multiple poses.
95 *
96 * @param out output SmallVector to hold 2D poses
97 * @return span referring to output SmallVector
98 */
99 std::span<const Pose2d> GetPoses(wpi::SmallVectorImpl<Pose2d>& out) const;
100
101 private:
102 void UpdateEntry(bool setDefault = false);
103 void UpdateFromEntry() const;
104
105 mutable wpi::mutex m_mutex;
106 std::string m_name;
107 nt::DoubleArrayEntry m_entry;
108 mutable wpi::SmallVector<Pose2d, 1> m_poses;
109};
110
111} // namespace frc
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:23
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:23
Represents a time-parameterized trajectory.
Definition: Trajectory.h:25
NetworkTables DoubleArray entry.
Definition: DoubleArrayTopic.h:212
This is a 'vector' (really, a variable-sized array), optimized for the case when the array is small.
Definition: SmallVector.h:1202
This class consists of common code factored out of the SmallVector class to reduce code duplication b...
Definition: SmallVector.h:579
basic_string_view< char > string_view
Definition: core.h:501
Definition: AprilTagPoseEstimator.h:15
::std::mutex mutex
Definition: mutex.h:17