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