WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
Field2d.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 <memory>
8#include <string_view>
9#include <vector>
10
13#include "wpi/nt/NTSendable.hpp"
17#include "wpi/units/length.hpp"
18#include "wpi/util/mutex.hpp"
20
21namespace wpi {
22
23/**
24 * 2D representation of game field for dashboards.
25 *
26 * An object's pose is the location shown on the dashboard view. Note that
27 * for the robot, this may or may not match the internal odometry. For example,
28 * if the robot is shown at a particular starting location, the pose in this
29 * class would represent the actual location on the field, but the robot's
30 * internal state might have a 0,0,0 pose (unless it's initialized to
31 * something different).
32 *
33 * As the user is able to edit the pose, code performing updates should get
34 * the robot pose, transform it as appropriate (e.g. based on wheel odometry),
35 * and set the new pose.
36 *
37 * This class provides methods to set the robot pose, but other objects can
38 * also be shown by using the GetObject() function. Other objects can
39 * also have multiple poses (which will show the object at multiple locations).
40 */
42 public wpi::util::SendableHelper<Field2d> {
43 public:
44 using Entry = size_t;
45
47
50
51 /**
52 * Set the robot pose from a Pose object.
53 *
54 * @param pose 2D pose
55 */
57
58 /**
59 * Set the robot pose from x, y, and rotation.
60 *
61 * @param x X location
62 * @param y Y location
63 * @param rotation rotation
64 */
65 void SetRobotPose(wpi::units::meter_t x, wpi::units::meter_t y,
66 wpi::math::Rotation2d rotation);
67
68 /**
69 * Get the robot pose.
70 *
71 * @return 2D pose
72 */
74
75 /**
76 * Get or create a field object.
77 *
78 * @return Field object
79 */
80 FieldObject2d* GetObject(std::string_view name);
81
82 /**
83 * Get the robot object.
84 *
85 * @return Field object for robot
86 */
88
90
91 private:
92 std::shared_ptr<wpi::nt::NetworkTable> m_table;
93
94 mutable wpi::util::mutex m_mutex;
95 std::vector<std::unique_ptr<FieldObject2d>> m_objects;
96};
97
98} // namespace wpi
@ name
Definition base.h:690
void SetRobotPose(const wpi::math::Pose2d &pose)
Set the robot pose from a Pose object.
size_t Entry
Definition Field2d.hpp:44
Field2d(Field2d &&rhs)
void SetRobotPose(wpi::units::meter_t x, wpi::units::meter_t y, wpi::math::Rotation2d rotation)
Set the robot pose from x, y, and rotation.
FieldObject2d * GetObject(std::string_view name)
Get or create a field object.
wpi::math::Pose2d GetRobotPose() const
Get the robot pose.
Field2d & operator=(Field2d &&rhs)
void InitSendable(wpi::nt::NTSendableBuilder &builder) override
Initializes this Sendable object.
FieldObject2d * GetRobotObject()
Get the robot object.
Game field object on a Field2d.
Definition FieldObject2d.hpp:31
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
Helper class for building Sendable dashboard representations for NetworkTables.
Definition NTSendableBuilder.hpp:21
Interface for NetworkTable Sendable objects.
Definition NTSendable.hpp:16
A helper class for use with objects that add themselves to SendableRegistry.
Definition SendableHelper.hpp:21
::std::mutex mutex
Definition mutex.hpp:17
Definition CvSource.hpp:15