WPILibC++ 2024.1.1-beta-4
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 <utility>
12#include <vector>
13
15#include <units/length.h>
16#include <wpi/SmallVector.h>
17#include <wpi/mutex.h>
18
19#include "frc/geometry/Pose2d.h"
21
22namespace frc {
23
24class Field2d;
25class Trajectory;
26
27/**
28 * Game field object on a Field2d.
29 */
31 friend class Field2d;
32 struct private_init {};
33
34 public:
35 FieldObject2d(std::string_view name, const private_init&) : m_name{name} {}
36
39
40 /**
41 * Set the pose from a Pose object.
42 *
43 * @param pose 2D pose
44 */
45 void SetPose(const Pose2d& pose);
46
47 /**
48 * Set the pose from x, y, and rotation.
49 *
50 * @param x X location
51 * @param y Y location
52 * @param rotation rotation
53 */
54 void SetPose(units::meter_t x, units::meter_t y, Rotation2d rotation);
55
56 /**
57 * Get the pose.
58 *
59 * @return 2D pose, or 0,0,0 if unknown / does not exist
60 */
61 Pose2d GetPose() const;
62
63 /**
64 * Set multiple poses from an array of Pose objects.
65 * The total number of poses is limited to 85.
66 *
67 * @param poses array of 2D poses
68 */
69 void SetPoses(std::span<const Pose2d> poses);
70
71 /**
72 * Set multiple poses from an array of Pose objects.
73 * The total number of poses is limited to 85.
74 *
75 * @param poses array of 2D poses
76 */
77 void SetPoses(std::initializer_list<Pose2d> poses);
78
79 /**
80 * Sets poses from a trajectory.
81 *
82 * @param trajectory The trajectory from which poses should be added.
83 */
84 void SetTrajectory(const Trajectory& trajectory);
85
86 /**
87 * Get multiple poses.
88 *
89 * @param obj Object entry
90 * @return vector of 2D poses
91 */
92 std::vector<Pose2d> GetPoses() const;
93
94 /**
95 * Get multiple poses.
96 *
97 * @param out output SmallVector to hold 2D poses
98 * @return span referring to output SmallVector
99 */
100 std::span<const Pose2d> GetPoses(wpi::SmallVectorImpl<Pose2d>& out) const;
101
102 private:
103 void UpdateEntry(bool setDefault = false);
104 void UpdateFromEntry() const;
105
106 mutable wpi::mutex m_mutex;
107 std::string m_name;
108 nt::DoubleArrayEntry m_entry;
109 mutable wpi::SmallVector<Pose2d, 1> m_poses;
110};
111
112} // 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:30
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:35
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