diff --git a/styleguide/spotbugs-exclude.xml b/styleguide/spotbugs-exclude.xml
index feec066961..5b88ef0e8c 100644
--- a/styleguide/spotbugs-exclude.xml
+++ b/styleguide/spotbugs-exclude.xml
@@ -15,6 +15,10 @@
+
+
+
+
diff --git a/wpilibc/src/main/native/cpp/smartdashboard/MechanismLigament2d.cpp b/wpilibc/src/main/native/cpp/smartdashboard/MechanismLigament2d.cpp
index 175db0da8d..6d65600af3 100644
--- a/wpilibc/src/main/native/cpp/smartdashboard/MechanismLigament2d.cpp
+++ b/wpilibc/src/main/native/cpp/smartdashboard/MechanismLigament2d.cpp
@@ -21,7 +21,6 @@ MechanismLigament2d::MechanismLigament2d(std::string_view name, double length,
void MechanismLigament2d::UpdateEntries(
std::shared_ptr table) {
- std::scoped_lock lock(m_mutex);
table->GetEntry(".type").SetString("line");
m_colorEntry = table->GetEntry("color");
diff --git a/wpilibc/src/main/native/cpp/smartdashboard/MechanismRoot2d.cpp b/wpilibc/src/main/native/cpp/smartdashboard/MechanismRoot2d.cpp
index 07d15f0118..637b24b0f2 100644
--- a/wpilibc/src/main/native/cpp/smartdashboard/MechanismRoot2d.cpp
+++ b/wpilibc/src/main/native/cpp/smartdashboard/MechanismRoot2d.cpp
@@ -20,14 +20,12 @@ void MechanismRoot2d::SetPosition(double x, double y) {
}
void MechanismRoot2d::UpdateEntries(std::shared_ptr table) {
- std::scoped_lock lock(m_mutex);
m_xEntry = table->GetEntry("x");
m_yEntry = table->GetEntry("y");
Flush();
}
inline void MechanismRoot2d::Flush() {
- std::scoped_lock lock(m_mutex);
if (m_xEntry) {
m_xEntry.SetDouble(m_x);
}
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismLigament2d.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismLigament2d.java
index 8579936e33..774ab29e86 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismLigament2d.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismLigament2d.java
@@ -128,7 +128,7 @@ public class MechanismLigament2d extends MechanismObject2d {
}
@Override
- protected synchronized void updateEntries(NetworkTable table) {
+ protected void updateEntries(NetworkTable table) {
table.getEntry(".type").setString("line");
m_angleEntry = table.getEntry("angle");
m_lengthEntry = table.getEntry("length");
@@ -138,7 +138,7 @@ public class MechanismLigament2d extends MechanismObject2d {
}
/** Flush latest data to NT. */
- private synchronized void flush() {
+ private void flush() {
if (m_angleEntry != null) {
m_angleEntry.setDouble(m_angle);
}
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismObject2d.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismObject2d.java
index 4598f7ee95..584660aa85 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismObject2d.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismObject2d.java
@@ -52,7 +52,7 @@ public abstract class MechanismObject2d {
return object;
}
- final void update(NetworkTable table) {
+ final synchronized void update(NetworkTable table) {
m_table = table;
updateEntries(m_table);
for (MechanismObject2d obj : m_objects.values()) {
diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismRoot2d.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismRoot2d.java
index 39f4515493..eef73d4fbc 100644
--- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismRoot2d.java
+++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/MechanismRoot2d.java
@@ -86,7 +86,7 @@ public final class MechanismRoot2d {
return m_name;
}
- private synchronized void flush() {
+ private void flush() {
if (m_xEntry != null) {
m_xEntry.setDouble(m_x);
}