WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
FieldObject2d.hpp
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
16#include "wpi/units/length.hpp"
17#include "wpi/util/SmallVector.hpp"
18#include "wpi/util/mutex.hpp"
19
20namespace wpi::math {
21class Trajectory;
22}
23
24namespace wpi {
25
26class Field2d;
27
28/**
29 * Game field object on a Field2d.
30 */
32 friend class Field2d;
33 struct private_init {};
34
35 public:
36 FieldObject2d(std::string_view name, const private_init&) : m_name{name} {}
37
40
41 /**
42 * Set the pose from a Pose object.
43 *
44 * @param pose 2D pose
45 */
46 void SetPose(const wpi::math::Pose2d& pose);
47
48 /**
49 * Set the pose from x, y, and rotation.
50 *
51 * @param x X location
52 * @param y Y location
53 * @param rotation rotation
54 */
55 void SetPose(wpi::units::meter_t x, wpi::units::meter_t y,
56 wpi::math::Rotation2d rotation);
57
58 /**
59 * Get the pose.
60 *
61 * @return 2D pose, or 0,0,0 if unknown / does not exist
62 */
64
65 /**
66 * Set multiple poses from an array of Pose objects.
67 * The total number of poses is limited to 85.
68 *
69 * @param poses array of 2D poses
70 */
71 void SetPoses(std::span<const wpi::math::Pose2d> poses);
72
73 /**
74 * Set multiple poses from an array of Pose objects.
75 * The total number of poses is limited to 85.
76 *
77 * @param poses array of 2D poses
78 */
79 void SetPoses(std::initializer_list<wpi::math::Pose2d> poses);
80
81 /**
82 * Sets poses from a trajectory.
83 *
84 * @param trajectory The trajectory from which poses should be added.
85 */
86 void SetTrajectory(const wpi::math::Trajectory& trajectory);
87
88 /**
89 * Get multiple poses.
90 *
91 * @return vector of 2D poses
92 */
93 std::vector<wpi::math::Pose2d> GetPoses() const;
94
95 /**
96 * Get multiple poses.
97 *
98 * @param out output wpi::util::SmallVector to hold 2D poses
99 * @return span referring to output wpi::util::SmallVector
100 */
101 std::span<const wpi::math::Pose2d> GetPoses(
103
104 private:
105 void UpdateEntry(bool setDefault = false);
106 void UpdateFromEntry() const;
107
108 mutable wpi::util::mutex m_mutex;
109 std::string m_name;
111 mutable wpi::util::SmallVector<wpi::math::Pose2d, 1> m_poses;
112};
113
114} // namespace wpi
@ name
Definition base.h:690
2D representation of game field for dashboards.
Definition Field2d.hpp:42
void SetPoses(std::initializer_list< wpi::math::Pose2d > poses)
Set multiple poses from an array of Pose objects.
void SetPose(const wpi::math::Pose2d &pose)
Set the pose from a Pose object.
wpi::math::Pose2d GetPose() const
Get the pose.
FieldObject2d & operator=(FieldObject2d &&rhs)
friend class Field2d
Definition FieldObject2d.hpp:32
FieldObject2d(std::string_view name, const private_init &)
Definition FieldObject2d.hpp:36
std::span< const wpi::math::Pose2d > GetPoses(wpi::util::SmallVectorImpl< wpi::math::Pose2d > &out) const
Get multiple poses.
void SetPoses(std::span< const wpi::math::Pose2d > poses)
Set multiple poses from an array of Pose objects.
std::vector< wpi::math::Pose2d > GetPoses() const
Get multiple poses.
FieldObject2d(FieldObject2d &&rhs)
void SetPose(wpi::units::meter_t x, wpi::units::meter_t y, wpi::math::Rotation2d rotation)
Set the pose from x, y, and rotation.
void SetTrajectory(const wpi::math::Trajectory &trajectory)
Sets poses from a trajectory.
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.hpp:27
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.hpp:26
Represents a time-parameterized trajectory.
Definition Trajectory.hpp:28
NetworkTables DoubleArray entry.
Definition DoubleArrayTopic.hpp:238
Definition BooleanTopic.hpp:24
Definition LinearSystem.hpp:20
::std::mutex mutex
Definition mutex.hpp:17
Definition CvSource.hpp:15