Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 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 | #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 | |
| 18 | using namespace glass; |
| 19 | |
| 20 | // Convert "#RRGGBB" hex color to ImU32 color |
| 21 | static 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 | |
| 31 | namespace { |
| 32 | |
| 33 | class NTMechanismObjectModel; |
| 34 | |
| 35 | class NTMechanismGroupImpl final { |
| 36 | public: |
James Kuszmaul | cf32412 | 2023-01-14 14:07:17 -0800 | [diff] [blame^] | 37 | NTMechanismGroupImpl(nt::NetworkTableInstance inst, std::string_view path, |
Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 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); |
James Kuszmaul | cf32412 | 2023-01-14 14:07:17 -0800 | [diff] [blame^] | 43 | |
| 44 | void NTUpdate(const nt::Event& event, std::string_view name); |
Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 45 | |
| 46 | protected: |
James Kuszmaul | cf32412 | 2023-01-14 14:07:17 -0800 | [diff] [blame^] | 47 | nt::NetworkTableInstance m_inst; |
Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 48 | std::string m_path; |
| 49 | std::string m_name; |
| 50 | std::vector<std::unique_ptr<NTMechanismObjectModel>> m_objects; |
| 51 | }; |
| 52 | |
| 53 | class NTMechanismObjectModel final : public MechanismObjectModel { |
| 54 | public: |
James Kuszmaul | cf32412 | 2023-01-14 14:07:17 -0800 | [diff] [blame^] | 55 | NTMechanismObjectModel(nt::NetworkTableInstance inst, std::string_view path, |
Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 56 | std::string_view name) |
| 57 | : m_group{inst, path, name}, |
James Kuszmaul | cf32412 | 2023-01-14 14:07:17 -0800 | [diff] [blame^] | 58 | m_typeTopic{inst.GetTopic(fmt::format("{}/.type", path))}, |
| 59 | m_colorTopic{inst.GetTopic(fmt::format("{}/color", path))}, |
| 60 | m_weightTopic{inst.GetTopic(fmt::format("{}/weight", path))}, |
| 61 | m_angleTopic{inst.GetTopic(fmt::format("{}/angle", path))}, |
| 62 | m_lengthTopic{inst.GetTopic(fmt::format("{}/length", path))} {} |
Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 63 | |
| 64 | const char* GetName() const final { return m_group.GetName(); } |
| 65 | void ForEachObject( |
| 66 | wpi::function_ref<void(MechanismObjectModel& model)> func) final { |
| 67 | m_group.ForEachObject(func); |
| 68 | } |
| 69 | |
| 70 | const char* GetType() const final { return m_typeValue.c_str(); } |
| 71 | ImU32 GetColor() const final { return m_colorValue; } |
| 72 | double GetWeight() const final { return m_weightValue; } |
| 73 | frc::Rotation2d GetAngle() const final { return m_angleValue; } |
| 74 | units::meter_t GetLength() const final { return m_lengthValue; } |
| 75 | |
James Kuszmaul | cf32412 | 2023-01-14 14:07:17 -0800 | [diff] [blame^] | 76 | bool NTUpdate(const nt::Event& event, std::string_view name); |
Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 77 | |
| 78 | private: |
| 79 | NTMechanismGroupImpl m_group; |
| 80 | |
James Kuszmaul | cf32412 | 2023-01-14 14:07:17 -0800 | [diff] [blame^] | 81 | nt::Topic m_typeTopic; |
| 82 | nt::Topic m_colorTopic; |
| 83 | nt::Topic m_weightTopic; |
| 84 | nt::Topic m_angleTopic; |
| 85 | nt::Topic m_lengthTopic; |
Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 86 | |
| 87 | std::string m_typeValue; |
| 88 | ImU32 m_colorValue = IM_COL32_WHITE; |
| 89 | double m_weightValue = 1.0; |
| 90 | frc::Rotation2d m_angleValue; |
| 91 | units::meter_t m_lengthValue = 0.0_m; |
| 92 | }; |
| 93 | |
| 94 | } // namespace |
| 95 | |
| 96 | void NTMechanismGroupImpl::ForEachObject( |
| 97 | wpi::function_ref<void(MechanismObjectModel& model)> func) { |
| 98 | for (auto&& obj : m_objects) { |
| 99 | func(*obj); |
| 100 | } |
| 101 | } |
| 102 | |
James Kuszmaul | cf32412 | 2023-01-14 14:07:17 -0800 | [diff] [blame^] | 103 | void NTMechanismGroupImpl::NTUpdate(const nt::Event& event, |
Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 104 | std::string_view name) { |
| 105 | if (name.empty()) { |
| 106 | return; |
| 107 | } |
| 108 | std::string_view childName; |
| 109 | std::tie(name, childName) = wpi::split(name, '/'); |
| 110 | if (childName.empty()) { |
| 111 | return; |
| 112 | } |
| 113 | |
| 114 | auto it = std::lower_bound( |
| 115 | m_objects.begin(), m_objects.end(), name, |
| 116 | [](const auto& e, std::string_view name) { return e->GetName() < name; }); |
| 117 | bool match = it != m_objects.end() && (*it)->GetName() == name; |
| 118 | |
James Kuszmaul | cf32412 | 2023-01-14 14:07:17 -0800 | [diff] [blame^] | 119 | if (event.GetTopicInfo()) { |
| 120 | if (event.flags & nt::EventFlags::kPublish) { |
| 121 | if (!match) { |
| 122 | it = m_objects.emplace( |
| 123 | it, std::make_unique<NTMechanismObjectModel>( |
| 124 | m_inst, fmt::format("{}/{}", m_path, name), name)); |
| 125 | match = true; |
| 126 | } |
Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 127 | } |
James Kuszmaul | cf32412 | 2023-01-14 14:07:17 -0800 | [diff] [blame^] | 128 | |
| 129 | if (match) { |
| 130 | if ((*it)->NTUpdate(event, childName)) { |
| 131 | m_objects.erase(it); |
| 132 | } |
| 133 | } |
| 134 | } else if (event.GetValueEventData()) { |
| 135 | if (match) { |
| 136 | (*it)->NTUpdate(event, childName); |
Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 137 | } |
| 138 | } |
| 139 | } |
| 140 | |
James Kuszmaul | cf32412 | 2023-01-14 14:07:17 -0800 | [diff] [blame^] | 141 | bool NTMechanismObjectModel::NTUpdate(const nt::Event& event, |
Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 142 | std::string_view childName) { |
James Kuszmaul | cf32412 | 2023-01-14 14:07:17 -0800 | [diff] [blame^] | 143 | if (auto info = event.GetTopicInfo()) { |
| 144 | if (info->topic == m_typeTopic.GetHandle()) { |
| 145 | if (event.flags & nt::EventFlags::kUnpublish) { |
| 146 | return true; |
| 147 | } |
| 148 | } else if (info->topic != m_colorTopic.GetHandle() && |
| 149 | info->topic != m_weightTopic.GetHandle() && |
| 150 | info->topic != m_angleTopic.GetHandle() && |
| 151 | info->topic != m_lengthTopic.GetHandle()) { |
| 152 | m_group.NTUpdate(event, childName); |
Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 153 | } |
James Kuszmaul | cf32412 | 2023-01-14 14:07:17 -0800 | [diff] [blame^] | 154 | } else if (auto valueData = event.GetValueEventData()) { |
| 155 | if (valueData->topic == m_typeTopic.GetHandle()) { |
| 156 | if (valueData->value && valueData->value.IsString()) { |
| 157 | m_typeValue = valueData->value.GetString(); |
| 158 | } |
| 159 | } else if (valueData->topic == m_colorTopic.GetHandle()) { |
| 160 | if (valueData->value && valueData->value.IsString()) { |
| 161 | ConvertColor(valueData->value.GetString(), &m_colorValue); |
| 162 | } |
| 163 | } else if (valueData->topic == m_weightTopic.GetHandle()) { |
| 164 | if (valueData->value && valueData->value.IsDouble()) { |
| 165 | m_weightValue = valueData->value.GetDouble(); |
| 166 | } |
| 167 | } else if (valueData->topic == m_angleTopic.GetHandle()) { |
| 168 | if (valueData->value && valueData->value.IsDouble()) { |
| 169 | m_angleValue = units::degree_t{valueData->value.GetDouble()}; |
| 170 | } |
| 171 | } else if (valueData->topic == m_lengthTopic.GetHandle()) { |
| 172 | if (valueData->value && valueData->value.IsDouble()) { |
| 173 | m_lengthValue = units::meter_t{valueData->value.GetDouble()}; |
| 174 | } |
| 175 | } else { |
| 176 | m_group.NTUpdate(event, childName); |
Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 177 | } |
Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 178 | } |
| 179 | return false; |
| 180 | } |
| 181 | |
| 182 | class NTMechanism2DModel::RootModel final : public MechanismRootModel { |
| 183 | public: |
James Kuszmaul | cf32412 | 2023-01-14 14:07:17 -0800 | [diff] [blame^] | 184 | RootModel(nt::NetworkTableInstance inst, std::string_view path, |
| 185 | std::string_view name) |
Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 186 | : m_group{inst, path, name}, |
James Kuszmaul | cf32412 | 2023-01-14 14:07:17 -0800 | [diff] [blame^] | 187 | m_xTopic{inst.GetTopic(fmt::format("{}/x", path))}, |
| 188 | m_yTopic{inst.GetTopic(fmt::format("{}/y", path))} {} |
Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 189 | |
| 190 | const char* GetName() const final { return m_group.GetName(); } |
| 191 | void ForEachObject( |
| 192 | wpi::function_ref<void(MechanismObjectModel& model)> func) final { |
| 193 | m_group.ForEachObject(func); |
| 194 | } |
| 195 | |
James Kuszmaul | cf32412 | 2023-01-14 14:07:17 -0800 | [diff] [blame^] | 196 | bool NTUpdate(const nt::Event& event, std::string_view childName); |
Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 197 | |
| 198 | frc::Translation2d GetPosition() const override { return m_pos; }; |
| 199 | |
| 200 | private: |
| 201 | NTMechanismGroupImpl m_group; |
James Kuszmaul | cf32412 | 2023-01-14 14:07:17 -0800 | [diff] [blame^] | 202 | nt::Topic m_xTopic; |
| 203 | nt::Topic m_yTopic; |
Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 204 | frc::Translation2d m_pos; |
| 205 | }; |
| 206 | |
James Kuszmaul | cf32412 | 2023-01-14 14:07:17 -0800 | [diff] [blame^] | 207 | bool NTMechanism2DModel::RootModel::NTUpdate(const nt::Event& event, |
Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 208 | std::string_view childName) { |
James Kuszmaul | cf32412 | 2023-01-14 14:07:17 -0800 | [diff] [blame^] | 209 | if (auto info = event.GetTopicInfo()) { |
| 210 | if (info->topic == m_xTopic.GetHandle() || |
| 211 | info->topic == m_yTopic.GetHandle()) { |
| 212 | if (event.flags & nt::EventFlags::kUnpublish) { |
| 213 | return true; |
| 214 | } |
| 215 | } else { |
| 216 | m_group.NTUpdate(event, childName); |
Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 217 | } |
James Kuszmaul | cf32412 | 2023-01-14 14:07:17 -0800 | [diff] [blame^] | 218 | } else if (auto valueData = event.GetValueEventData()) { |
| 219 | if (valueData->topic == m_xTopic.GetHandle()) { |
| 220 | if (valueData->value && valueData->value.IsDouble()) { |
| 221 | m_pos = frc::Translation2d{units::meter_t{valueData->value.GetDouble()}, |
| 222 | m_pos.Y()}; |
| 223 | } |
| 224 | } else if (valueData->topic == m_yTopic.GetHandle()) { |
| 225 | if (valueData->value && valueData->value.IsDouble()) { |
| 226 | m_pos = frc::Translation2d{ |
| 227 | m_pos.X(), units::meter_t{valueData->value.GetDouble()}}; |
| 228 | } |
| 229 | } else { |
| 230 | m_group.NTUpdate(event, childName); |
Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 231 | } |
Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 232 | } |
| 233 | return false; |
| 234 | } |
| 235 | |
| 236 | NTMechanism2DModel::NTMechanism2DModel(std::string_view path) |
James Kuszmaul | cf32412 | 2023-01-14 14:07:17 -0800 | [diff] [blame^] | 237 | : NTMechanism2DModel{nt::NetworkTableInstance::GetDefault(), path} {} |
Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 238 | |
James Kuszmaul | cf32412 | 2023-01-14 14:07:17 -0800 | [diff] [blame^] | 239 | NTMechanism2DModel::NTMechanism2DModel(nt::NetworkTableInstance inst, |
| 240 | std::string_view path) |
| 241 | : m_inst{inst}, |
Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 242 | m_path{fmt::format("{}/", path)}, |
James Kuszmaul | cf32412 | 2023-01-14 14:07:17 -0800 | [diff] [blame^] | 243 | m_tableSub{inst, {{m_path}}, {.periodic = 0.05, .sendAll = true}}, |
| 244 | m_nameTopic{m_inst.GetTopic(fmt::format("{}/.name", path))}, |
| 245 | m_dimensionsTopic{m_inst.GetTopic(fmt::format("{}/dims", path))}, |
| 246 | m_bgColorTopic{m_inst.GetTopic(fmt::format("{}/backgroundColor", path))}, |
| 247 | m_poller{m_inst}, |
Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 248 | m_dimensionsValue{1_m, 1_m} { |
James Kuszmaul | cf32412 | 2023-01-14 14:07:17 -0800 | [diff] [blame^] | 249 | m_poller.AddListener(m_tableSub, nt::EventFlags::kTopic | |
| 250 | nt::EventFlags::kValueAll | |
| 251 | nt::EventFlags::kImmediate); |
Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 252 | } |
| 253 | |
| 254 | NTMechanism2DModel::~NTMechanism2DModel() = default; |
| 255 | |
| 256 | void NTMechanism2DModel::Update() { |
James Kuszmaul | cf32412 | 2023-01-14 14:07:17 -0800 | [diff] [blame^] | 257 | for (auto&& event : m_poller.ReadQueue()) { |
| 258 | if (auto info = event.GetTopicInfo()) { |
| 259 | auto name = wpi::drop_front(info->name, m_path.size()); |
Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 260 | if (name.empty() || name[0] == '.') { |
| 261 | continue; |
| 262 | } |
| 263 | std::string_view childName; |
| 264 | std::tie(name, childName) = wpi::split(name, '/'); |
| 265 | if (childName.empty()) { |
| 266 | continue; |
| 267 | } |
| 268 | |
| 269 | auto it = std::lower_bound(m_roots.begin(), m_roots.end(), name, |
| 270 | [](const auto& e, std::string_view name) { |
| 271 | return e->GetName() < name; |
| 272 | }); |
| 273 | bool match = it != m_roots.end() && (*it)->GetName() == name; |
| 274 | |
James Kuszmaul | cf32412 | 2023-01-14 14:07:17 -0800 | [diff] [blame^] | 275 | if (event.flags & nt::EventFlags::kPublish) { |
Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 276 | if (!match) { |
| 277 | it = m_roots.emplace( |
James Kuszmaul | cf32412 | 2023-01-14 14:07:17 -0800 | [diff] [blame^] | 278 | it, std::make_unique<RootModel>( |
| 279 | m_inst, fmt::format("{}{}", m_path, name), name)); |
Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 280 | match = true; |
| 281 | } |
| 282 | } |
| 283 | if (match) { |
| 284 | if ((*it)->NTUpdate(event, childName)) { |
| 285 | m_roots.erase(it); |
| 286 | } |
| 287 | } |
James Kuszmaul | cf32412 | 2023-01-14 14:07:17 -0800 | [diff] [blame^] | 288 | } else if (auto valueData = event.GetValueEventData()) { |
| 289 | if (valueData->topic == m_nameTopic.GetHandle()) { |
| 290 | // .name |
| 291 | if (valueData->value && valueData->value.IsString()) { |
| 292 | m_nameValue = valueData->value.GetString(); |
| 293 | } |
| 294 | } else if (valueData->topic == m_dimensionsTopic.GetHandle()) { |
| 295 | // dims |
| 296 | if (valueData->value && valueData->value.IsDoubleArray()) { |
| 297 | auto arr = valueData->value.GetDoubleArray(); |
| 298 | if (arr.size() == 2) { |
| 299 | m_dimensionsValue = frc::Translation2d{units::meter_t{arr[0]}, |
| 300 | units::meter_t{arr[1]}}; |
| 301 | } |
| 302 | } |
| 303 | } else if (valueData->topic == m_bgColorTopic.GetHandle()) { |
| 304 | // backgroundColor |
| 305 | if (valueData->value && valueData->value.IsString()) { |
| 306 | ConvertColor(valueData->value.GetString(), &m_bgColorValue); |
| 307 | } |
| 308 | } else { |
| 309 | auto fullName = nt::Topic{valueData->topic}.GetName(); |
| 310 | auto name = wpi::drop_front(fullName, m_path.size()); |
| 311 | if (name.empty() || name[0] == '.') { |
| 312 | continue; |
| 313 | } |
| 314 | std::string_view childName; |
| 315 | std::tie(name, childName) = wpi::split(name, '/'); |
| 316 | if (childName.empty()) { |
| 317 | continue; |
| 318 | } |
| 319 | |
| 320 | auto it = std::lower_bound(m_roots.begin(), m_roots.end(), name, |
| 321 | [](const auto& e, std::string_view name) { |
| 322 | return e->GetName() < name; |
| 323 | }); |
| 324 | if (it != m_roots.end() && (*it)->GetName() == name) { |
| 325 | if ((*it)->NTUpdate(event, childName)) { |
| 326 | m_roots.erase(it); |
| 327 | } |
| 328 | } |
| 329 | } |
Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 330 | } |
| 331 | } |
| 332 | } |
| 333 | |
| 334 | bool NTMechanism2DModel::Exists() { |
James Kuszmaul | cf32412 | 2023-01-14 14:07:17 -0800 | [diff] [blame^] | 335 | return m_nameTopic.Exists(); |
Austin Schuh | 812d0d1 | 2021-11-04 20:16:48 -0700 | [diff] [blame] | 336 | } |
| 337 | |
| 338 | bool NTMechanism2DModel::IsReadOnly() { |
| 339 | return false; |
| 340 | } |
| 341 | |
| 342 | void NTMechanism2DModel::ForEachRoot( |
| 343 | wpi::function_ref<void(MechanismRootModel& model)> func) { |
| 344 | for (auto&& obj : m_roots) { |
| 345 | func(*obj); |
| 346 | } |
| 347 | } |