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/NTField2D.h" |
| 6 | |
| 7 | #include <algorithm> |
| 8 | #include <vector> |
| 9 | |
| 10 | #include <fmt/format.h> |
| 11 | #include <ntcore_cpp.h> |
| 12 | #include <wpi/Endian.h> |
| 13 | #include <wpi/MathExtras.h> |
| 14 | #include <wpi/SmallVector.h> |
| 15 | #include <wpi/StringExtras.h> |
| 16 | |
| 17 | using namespace glass; |
| 18 | |
| 19 | class NTField2DModel::ObjectModel : public FieldObjectModel { |
| 20 | public: |
| 21 | ObjectModel(std::string_view name, NT_Entry entry) |
| 22 | : m_name{name}, m_entry{entry} {} |
| 23 | |
| 24 | const char* GetName() const override { return m_name.c_str(); } |
| 25 | NT_Entry GetEntry() const { return m_entry; } |
| 26 | |
| 27 | void NTUpdate(const nt::Value& value); |
| 28 | |
| 29 | void Update() override { |
| 30 | if (auto value = nt::GetEntryValue(m_entry)) { |
| 31 | NTUpdate(*value); |
| 32 | } |
| 33 | } |
| 34 | bool Exists() override { return nt::GetEntryType(m_entry) != NT_UNASSIGNED; } |
| 35 | bool IsReadOnly() override { return false; } |
| 36 | |
| 37 | wpi::span<const frc::Pose2d> GetPoses() override { return m_poses; } |
| 38 | void SetPoses(wpi::span<const frc::Pose2d> poses) override; |
| 39 | void SetPose(size_t i, frc::Pose2d pose) override; |
| 40 | void SetPosition(size_t i, frc::Translation2d pos) override; |
| 41 | void SetRotation(size_t i, frc::Rotation2d rot) override; |
| 42 | |
| 43 | private: |
| 44 | void UpdateNT(); |
| 45 | |
| 46 | std::string m_name; |
| 47 | NT_Entry m_entry; |
| 48 | |
| 49 | std::vector<frc::Pose2d> m_poses; |
| 50 | }; |
| 51 | |
| 52 | void NTField2DModel::ObjectModel::NTUpdate(const nt::Value& value) { |
| 53 | if (value.IsDoubleArray()) { |
| 54 | auto arr = value.GetDoubleArray(); |
| 55 | auto size = arr.size(); |
| 56 | if ((size % 3) != 0) { |
| 57 | return; |
| 58 | } |
| 59 | m_poses.resize(size / 3); |
| 60 | for (size_t i = 0; i < size / 3; ++i) { |
| 61 | m_poses[i] = frc::Pose2d{ |
| 62 | units::meter_t{arr[i * 3 + 0]}, units::meter_t{arr[i * 3 + 1]}, |
| 63 | frc::Rotation2d{units::degree_t{arr[i * 3 + 2]}}}; |
| 64 | } |
| 65 | } else if (value.IsRaw()) { |
| 66 | // treat it simply as an array of doubles |
| 67 | std::string_view data = value.GetRaw(); |
| 68 | |
| 69 | // must be triples of doubles |
| 70 | auto size = data.size(); |
| 71 | if ((size % (3 * 8)) != 0) { |
| 72 | return; |
| 73 | } |
| 74 | m_poses.resize(size / (3 * 8)); |
| 75 | const char* p = data.data(); |
| 76 | for (size_t i = 0; i < size / (3 * 8); ++i) { |
| 77 | double x = wpi::BitsToDouble( |
| 78 | wpi::support::endian::readNext<uint64_t, wpi::support::big, |
| 79 | wpi::support::unaligned>(p)); |
| 80 | double y = wpi::BitsToDouble( |
| 81 | wpi::support::endian::readNext<uint64_t, wpi::support::big, |
| 82 | wpi::support::unaligned>(p)); |
| 83 | double rot = wpi::BitsToDouble( |
| 84 | wpi::support::endian::readNext<uint64_t, wpi::support::big, |
| 85 | wpi::support::unaligned>(p)); |
| 86 | m_poses[i] = frc::Pose2d{units::meter_t{x}, units::meter_t{y}, |
| 87 | frc::Rotation2d{units::degree_t{rot}}}; |
| 88 | } |
| 89 | } |
| 90 | } |
| 91 | |
| 92 | void NTField2DModel::ObjectModel::UpdateNT() { |
| 93 | if (m_poses.size() < (255 / 3)) { |
| 94 | wpi::SmallVector<double, 9> arr; |
| 95 | for (auto&& pose : m_poses) { |
| 96 | auto& translation = pose.Translation(); |
| 97 | arr.push_back(translation.X().value()); |
| 98 | arr.push_back(translation.Y().value()); |
| 99 | arr.push_back(pose.Rotation().Degrees().value()); |
| 100 | } |
| 101 | nt::SetEntryTypeValue(m_entry, nt::Value::MakeDoubleArray(arr)); |
| 102 | } else { |
| 103 | // send as raw array of doubles if too big for NT array |
| 104 | std::vector<char> arr; |
| 105 | arr.resize(m_poses.size() * 3 * 8); |
| 106 | char* p = arr.data(); |
| 107 | for (auto&& pose : m_poses) { |
| 108 | auto& translation = pose.Translation(); |
| 109 | wpi::support::endian::write64be( |
| 110 | p, wpi::DoubleToBits(translation.X().value())); |
| 111 | p += 8; |
| 112 | wpi::support::endian::write64be( |
| 113 | p, wpi::DoubleToBits(translation.Y().value())); |
| 114 | p += 8; |
| 115 | wpi::support::endian::write64be( |
| 116 | p, wpi::DoubleToBits(pose.Rotation().Degrees().value())); |
| 117 | p += 8; |
| 118 | } |
| 119 | nt::SetEntryTypeValue(m_entry, |
| 120 | nt::Value::MakeRaw({arr.data(), arr.size()})); |
| 121 | } |
| 122 | } |
| 123 | |
| 124 | void NTField2DModel::ObjectModel::SetPoses(wpi::span<const frc::Pose2d> poses) { |
| 125 | m_poses.assign(poses.begin(), poses.end()); |
| 126 | UpdateNT(); |
| 127 | } |
| 128 | |
| 129 | void NTField2DModel::ObjectModel::SetPose(size_t i, frc::Pose2d pose) { |
| 130 | if (i < m_poses.size()) { |
| 131 | m_poses[i] = pose; |
| 132 | UpdateNT(); |
| 133 | } |
| 134 | } |
| 135 | |
| 136 | void NTField2DModel::ObjectModel::SetPosition(size_t i, |
| 137 | frc::Translation2d pos) { |
| 138 | if (i < m_poses.size()) { |
| 139 | m_poses[i] = frc::Pose2d{pos, m_poses[i].Rotation()}; |
| 140 | UpdateNT(); |
| 141 | } |
| 142 | } |
| 143 | |
| 144 | void NTField2DModel::ObjectModel::SetRotation(size_t i, frc::Rotation2d rot) { |
| 145 | if (i < m_poses.size()) { |
| 146 | m_poses[i] = frc::Pose2d{m_poses[i].Translation(), rot}; |
| 147 | UpdateNT(); |
| 148 | } |
| 149 | } |
| 150 | |
| 151 | NTField2DModel::NTField2DModel(std::string_view path) |
| 152 | : NTField2DModel{nt::GetDefaultInstance(), path} {} |
| 153 | |
| 154 | NTField2DModel::NTField2DModel(NT_Inst inst, std::string_view path) |
| 155 | : m_nt{inst}, |
| 156 | m_path{fmt::format("{}/", path)}, |
| 157 | m_name{m_nt.GetEntry(fmt::format("{}/.name", path))} { |
| 158 | m_nt.AddListener(m_path, NT_NOTIFY_LOCAL | NT_NOTIFY_NEW | NT_NOTIFY_DELETE | |
| 159 | NT_NOTIFY_UPDATE | NT_NOTIFY_IMMEDIATE); |
| 160 | } |
| 161 | |
| 162 | NTField2DModel::~NTField2DModel() = default; |
| 163 | |
| 164 | void NTField2DModel::Update() { |
| 165 | for (auto&& event : m_nt.PollListener()) { |
| 166 | // .name |
| 167 | if (event.entry == m_name) { |
| 168 | if (event.value && event.value->IsString()) { |
| 169 | m_nameValue = event.value->GetString(); |
| 170 | } |
| 171 | continue; |
| 172 | } |
| 173 | |
| 174 | // common case: update of existing entry; search by entry |
| 175 | if (event.flags & NT_NOTIFY_UPDATE) { |
| 176 | auto it = std::find_if( |
| 177 | m_objects.begin(), m_objects.end(), |
| 178 | [&](const auto& e) { return e->GetEntry() == event.entry; }); |
| 179 | if (it != m_objects.end()) { |
| 180 | (*it)->NTUpdate(*event.value); |
| 181 | continue; |
| 182 | } |
| 183 | } |
| 184 | |
| 185 | // handle create/delete |
| 186 | std::string_view name = event.name; |
| 187 | if (wpi::starts_with(name, m_path)) { |
| 188 | name.remove_prefix(m_path.size()); |
| 189 | if (name.empty() || name[0] == '.') { |
| 190 | continue; |
| 191 | } |
| 192 | auto [it, match] = Find(event.name); |
| 193 | if (event.flags & NT_NOTIFY_DELETE) { |
| 194 | if (match) { |
| 195 | m_objects.erase(it); |
| 196 | } |
| 197 | continue; |
| 198 | } else if (event.flags & NT_NOTIFY_NEW) { |
| 199 | if (!match) { |
| 200 | it = m_objects.emplace( |
| 201 | it, std::make_unique<ObjectModel>(event.name, event.entry)); |
| 202 | } |
| 203 | } else if (!match) { |
| 204 | continue; |
| 205 | } |
| 206 | if (event.flags & (NT_NOTIFY_NEW | NT_NOTIFY_UPDATE)) { |
| 207 | (*it)->NTUpdate(*event.value); |
| 208 | } |
| 209 | } |
| 210 | } |
| 211 | } |
| 212 | |
| 213 | bool NTField2DModel::Exists() { |
| 214 | return m_nt.IsConnected() && nt::GetEntryType(m_name) != NT_UNASSIGNED; |
| 215 | } |
| 216 | |
| 217 | bool NTField2DModel::IsReadOnly() { |
| 218 | return false; |
| 219 | } |
| 220 | |
| 221 | FieldObjectModel* NTField2DModel::AddFieldObject(std::string_view name) { |
| 222 | auto fullName = fmt::format("{}{}", m_path, name); |
| 223 | auto [it, match] = Find(fullName); |
| 224 | if (!match) { |
| 225 | it = m_objects.emplace( |
| 226 | it, std::make_unique<ObjectModel>(fullName, m_nt.GetEntry(fullName))); |
| 227 | } |
| 228 | return it->get(); |
| 229 | } |
| 230 | |
| 231 | void NTField2DModel::RemoveFieldObject(std::string_view name) { |
| 232 | auto [it, match] = Find(fmt::format("{}{}", m_path, name)); |
| 233 | if (match) { |
| 234 | nt::DeleteEntry((*it)->GetEntry()); |
| 235 | m_objects.erase(it); |
| 236 | } |
| 237 | } |
| 238 | |
| 239 | void NTField2DModel::ForEachFieldObject( |
| 240 | wpi::function_ref<void(FieldObjectModel& model, std::string_view name)> |
| 241 | func) { |
| 242 | for (auto&& obj : m_objects) { |
| 243 | if (obj->Exists()) { |
| 244 | func(*obj, wpi::drop_front(obj->GetName(), m_path.size())); |
| 245 | } |
| 246 | } |
| 247 | } |
| 248 | |
| 249 | std::pair<NTField2DModel::Objects::iterator, bool> NTField2DModel::Find( |
| 250 | std::string_view fullName) { |
| 251 | auto it = std::lower_bound( |
| 252 | m_objects.begin(), m_objects.end(), fullName, |
| 253 | [](const auto& e, std::string_view name) { return e->GetName() < name; }); |
| 254 | return {it, it != m_objects.end() && (*it)->GetName() == fullName}; |
| 255 | } |