blob: 9c73af25326dac35e4a6c3cffcb73092bdf8dc8c [file] [log] [blame]
Austin Schuh812d0d12021-11-04 20:16:48 -07001// 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#include "glass/networktables/NTMechanism2D.h"
6
7#include <algorithm>
8#include <string_view>
9#include <vector>
10
11#include <fmt/format.h>
12#include <imgui.h>
13#include <ntcore_cpp.h>
14#include <wpi/StringExtras.h>
15
16#include "glass/other/Mechanism2D.h"
17
18using namespace glass;
19
20// Convert "#RRGGBB" hex color to ImU32 color
21static void ConvertColor(std::string_view in, ImU32* out) {
22 if (in.size() != 7 || in[0] != '#') {
23 return;
24 }
25 if (auto v = wpi::parse_integer<ImU32>(wpi::drop_front(in), 16)) {
26 ImU32 val = v.value();
27 *out = IM_COL32((val >> 16) & 0xff, (val >> 8) & 0xff, val & 0xff, 255);
28 }
29}
30
31namespace {
32
33class NTMechanismObjectModel;
34
35class NTMechanismGroupImpl final {
36 public:
37 NTMechanismGroupImpl(NT_Inst inst, std::string_view path,
38 std::string_view name)
39 : m_inst{inst}, m_path{path}, m_name{name} {}
40
41 const char* GetName() const { return m_name.c_str(); }
42 void ForEachObject(wpi::function_ref<void(MechanismObjectModel& model)> func);
43 void NTUpdate(const nt::EntryNotification& event, std::string_view name);
44
45 protected:
46 NT_Inst m_inst;
47 std::string m_path;
48 std::string m_name;
49 std::vector<std::unique_ptr<NTMechanismObjectModel>> m_objects;
50};
51
52class NTMechanismObjectModel final : public MechanismObjectModel {
53 public:
54 NTMechanismObjectModel(NT_Inst inst, std::string_view path,
55 std::string_view name)
56 : m_group{inst, path, name},
57 m_type{nt::GetEntry(inst, fmt::format("{}/.type", path))},
58 m_color{nt::GetEntry(inst, fmt::format("{}/color", path))},
59 m_weight{nt::GetEntry(inst, fmt::format("{}/weight", path))},
60 m_angle{nt::GetEntry(inst, fmt::format("{}/angle", path))},
61 m_length{nt::GetEntry(inst, fmt::format("{}/length", path))} {}
62
63 const char* GetName() const final { return m_group.GetName(); }
64 void ForEachObject(
65 wpi::function_ref<void(MechanismObjectModel& model)> func) final {
66 m_group.ForEachObject(func);
67 }
68
69 const char* GetType() const final { return m_typeValue.c_str(); }
70 ImU32 GetColor() const final { return m_colorValue; }
71 double GetWeight() const final { return m_weightValue; }
72 frc::Rotation2d GetAngle() const final { return m_angleValue; }
73 units::meter_t GetLength() const final { return m_lengthValue; }
74
75 bool NTUpdate(const nt::EntryNotification& event, std::string_view childName);
76
77 private:
78 NTMechanismGroupImpl m_group;
79
80 NT_Entry m_type;
81 NT_Entry m_color;
82 NT_Entry m_weight;
83 NT_Entry m_angle;
84 NT_Entry m_length;
85
86 std::string m_typeValue;
87 ImU32 m_colorValue = IM_COL32_WHITE;
88 double m_weightValue = 1.0;
89 frc::Rotation2d m_angleValue;
90 units::meter_t m_lengthValue = 0.0_m;
91};
92
93} // namespace
94
95void NTMechanismGroupImpl::ForEachObject(
96 wpi::function_ref<void(MechanismObjectModel& model)> func) {
97 for (auto&& obj : m_objects) {
98 func(*obj);
99 }
100}
101
102void NTMechanismGroupImpl::NTUpdate(const nt::EntryNotification& event,
103 std::string_view name) {
104 if (name.empty()) {
105 return;
106 }
107 std::string_view childName;
108 std::tie(name, childName) = wpi::split(name, '/');
109 if (childName.empty()) {
110 return;
111 }
112
113 auto it = std::lower_bound(
114 m_objects.begin(), m_objects.end(), name,
115 [](const auto& e, std::string_view name) { return e->GetName() < name; });
116 bool match = it != m_objects.end() && (*it)->GetName() == name;
117
118 if (event.flags & NT_NOTIFY_NEW) {
119 if (!match) {
120 it = m_objects.emplace(
121 it, std::make_unique<NTMechanismObjectModel>(
122 m_inst, fmt::format("{}/{}", m_path, name), name));
123 match = true;
124 }
125 }
126 if (match) {
127 if ((*it)->NTUpdate(event, childName)) {
128 m_objects.erase(it);
129 }
130 }
131}
132
133bool NTMechanismObjectModel::NTUpdate(const nt::EntryNotification& event,
134 std::string_view childName) {
135 if (event.entry == m_type) {
136 if ((event.flags & NT_NOTIFY_DELETE) != 0) {
137 return true;
138 }
139 if (event.value && event.value->IsString()) {
140 m_typeValue = event.value->GetString();
141 }
142 } else if (event.entry == m_color) {
143 if (event.value && event.value->IsString()) {
144 ConvertColor(event.value->GetString(), &m_colorValue);
145 }
146 } else if (event.entry == m_weight) {
147 if (event.value && event.value->IsDouble()) {
148 m_weightValue = event.value->GetDouble();
149 }
150 } else if (event.entry == m_angle) {
151 if (event.value && event.value->IsDouble()) {
152 m_angleValue = units::degree_t{event.value->GetDouble()};
153 }
154 } else if (event.entry == m_length) {
155 if (event.value && event.value->IsDouble()) {
156 m_lengthValue = units::meter_t{event.value->GetDouble()};
157 }
158 } else {
159 m_group.NTUpdate(event, childName);
160 }
161 return false;
162}
163
164class NTMechanism2DModel::RootModel final : public MechanismRootModel {
165 public:
166 RootModel(NT_Inst inst, std::string_view path, std::string_view name)
167 : m_group{inst, path, name},
168 m_x{nt::GetEntry(inst, fmt::format("{}/x", path))},
169 m_y{nt::GetEntry(inst, fmt::format("{}/y", path))} {}
170
171 const char* GetName() const final { return m_group.GetName(); }
172 void ForEachObject(
173 wpi::function_ref<void(MechanismObjectModel& model)> func) final {
174 m_group.ForEachObject(func);
175 }
176
177 bool NTUpdate(const nt::EntryNotification& event, std::string_view childName);
178
179 frc::Translation2d GetPosition() const override { return m_pos; };
180
181 private:
182 NTMechanismGroupImpl m_group;
183 NT_Entry m_x;
184 NT_Entry m_y;
185 frc::Translation2d m_pos;
186};
187
188bool NTMechanism2DModel::RootModel::NTUpdate(const nt::EntryNotification& event,
189 std::string_view childName) {
190 if ((event.flags & NT_NOTIFY_DELETE) != 0 &&
191 (event.entry == m_x || event.entry == m_y)) {
192 return true;
193 } else if (event.entry == m_x) {
194 if (event.value && event.value->IsDouble()) {
195 m_pos = frc::Translation2d{units::meter_t{event.value->GetDouble()},
196 m_pos.Y()};
197 }
198 } else if (event.entry == m_y) {
199 if (event.value && event.value->IsDouble()) {
200 m_pos = frc::Translation2d{m_pos.X(),
201 units::meter_t{event.value->GetDouble()}};
202 }
203 } else {
204 m_group.NTUpdate(event, childName);
205 }
206 return false;
207}
208
209NTMechanism2DModel::NTMechanism2DModel(std::string_view path)
210 : NTMechanism2DModel{nt::GetDefaultInstance(), path} {}
211
212NTMechanism2DModel::NTMechanism2DModel(NT_Inst inst, std::string_view path)
213 : m_nt{inst},
214 m_path{fmt::format("{}/", path)},
215 m_name{m_nt.GetEntry(fmt::format("{}/.name", path))},
216 m_dimensions{m_nt.GetEntry(fmt::format("{}/dims", path))},
217 m_bgColor{m_nt.GetEntry(fmt::format("{}/backgroundColor", path))},
218 m_dimensionsValue{1_m, 1_m} {
219 m_nt.AddListener(m_path, NT_NOTIFY_LOCAL | NT_NOTIFY_NEW | NT_NOTIFY_DELETE |
220 NT_NOTIFY_UPDATE | NT_NOTIFY_IMMEDIATE);
221}
222
223NTMechanism2DModel::~NTMechanism2DModel() = default;
224
225void NTMechanism2DModel::Update() {
226 for (auto&& event : m_nt.PollListener()) {
227 // .name
228 if (event.entry == m_name) {
229 if (event.value && event.value->IsString()) {
230 m_nameValue = event.value->GetString();
231 }
232 continue;
233 }
234
235 // dims
236 if (event.entry == m_dimensions) {
237 if (event.value && event.value->IsDoubleArray()) {
238 auto arr = event.value->GetDoubleArray();
239 if (arr.size() == 2) {
240 m_dimensionsValue = frc::Translation2d{units::meter_t{arr[0]},
241 units::meter_t{arr[1]}};
242 }
243 }
244 }
245
246 // backgroundColor
247 if (event.entry == m_bgColor) {
248 if (event.value && event.value->IsString()) {
249 ConvertColor(event.value->GetString(), &m_bgColorValue);
250 }
251 }
252
253 std::string_view name = event.name;
254 if (wpi::starts_with(name, m_path)) {
255 name.remove_prefix(m_path.size());
256 if (name.empty() || name[0] == '.') {
257 continue;
258 }
259 std::string_view childName;
260 std::tie(name, childName) = wpi::split(name, '/');
261 if (childName.empty()) {
262 continue;
263 }
264
265 auto it = std::lower_bound(m_roots.begin(), m_roots.end(), name,
266 [](const auto& e, std::string_view name) {
267 return e->GetName() < name;
268 });
269 bool match = it != m_roots.end() && (*it)->GetName() == name;
270
271 if (event.flags & NT_NOTIFY_NEW) {
272 if (!match) {
273 it = m_roots.emplace(
274 it,
275 std::make_unique<RootModel>(
276 m_nt.GetInstance(), fmt::format("{}{}", m_path, name), name));
277 match = true;
278 }
279 }
280 if (match) {
281 if ((*it)->NTUpdate(event, childName)) {
282 m_roots.erase(it);
283 }
284 }
285 }
286 }
287}
288
289bool NTMechanism2DModel::Exists() {
290 return m_nt.IsConnected() && nt::GetEntryType(m_name) != NT_UNASSIGNED;
291}
292
293bool NTMechanism2DModel::IsReadOnly() {
294 return false;
295}
296
297void NTMechanism2DModel::ForEachRoot(
298 wpi::function_ref<void(MechanismRootModel& model)> func) {
299 for (auto&& obj : m_roots) {
300 func(*obj);
301 }
302}