diff --git a/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasD435ToMultiSenseLeftEyeBridge.java b/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasD435ToMultiSenseLeftEyeBridge.java index e8e21734fb8..86d09564cd1 100644 --- a/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasD435ToMultiSenseLeftEyeBridge.java +++ b/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasD435ToMultiSenseLeftEyeBridge.java @@ -22,7 +22,7 @@ import us.ihmc.commons.UnitConversions; import us.ihmc.tools.thread.MissingThreadTools; import us.ihmc.tools.thread.ResettableExceptionHandlingExecutorService; -import us.ihmc.tools.thread.Throttler; +import us.ihmc.commons.thread.Throttler; import us.ihmc.utilities.ros.RosMainNode; import us.ihmc.utilities.ros.RosTools; import us.ihmc.utilities.ros.subscriber.AbstractRosTopicSubscriber; diff --git a/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasOusterL515ZED2FusedColoredROS1ToREABridge.java b/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasOusterL515ZED2FusedColoredROS1ToREABridge.java index 586ebf6831c..4493aeefddd 100644 --- a/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasOusterL515ZED2FusedColoredROS1ToREABridge.java +++ b/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasOusterL515ZED2FusedColoredROS1ToREABridge.java @@ -24,7 +24,7 @@ import us.ihmc.commons.UnitConversions; import us.ihmc.tools.thread.MissingThreadTools; import us.ihmc.tools.thread.ResettableExceptionHandlingExecutorService; -import us.ihmc.tools.thread.Throttler; +import us.ihmc.commons.thread.Throttler; import us.ihmc.utilities.ros.RosMainNode; import us.ihmc.utilities.ros.RosTools; import us.ihmc.utilities.ros.subscriber.AbstractRosTopicSubscriber; diff --git a/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasOusterROS1ToREABridge.java b/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasOusterROS1ToREABridge.java index b10e66c6916..ed7da99fac0 100644 --- a/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasOusterROS1ToREABridge.java +++ b/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasOusterROS1ToREABridge.java @@ -19,7 +19,7 @@ import us.ihmc.commons.UnitConversions; import us.ihmc.tools.thread.MissingThreadTools; import us.ihmc.tools.thread.ResettableExceptionHandlingExecutorService; -import us.ihmc.tools.thread.Throttler; +import us.ihmc.commons.thread.Throttler; import us.ihmc.utilities.ros.RosMainNode; import us.ihmc.utilities.ros.RosTools; import us.ihmc.utilities.ros.subscriber.AbstractRosTopicSubscriber; diff --git a/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasZED2LeftEyeToMultiSenseLeftEyeBridge.java b/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasZED2LeftEyeToMultiSenseLeftEyeBridge.java index 7a4ab81eac6..ce5c71ea8df 100644 --- a/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasZED2LeftEyeToMultiSenseLeftEyeBridge.java +++ b/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasZED2LeftEyeToMultiSenseLeftEyeBridge.java @@ -28,7 +28,7 @@ import us.ihmc.commons.UnitConversions; import us.ihmc.tools.thread.MissingThreadTools; import us.ihmc.tools.thread.ResettableExceptionHandlingExecutorService; -import us.ihmc.tools.thread.Throttler; +import us.ihmc.commons.thread.Throttler; import us.ihmc.utilities.ros.RosMainNode; import us.ihmc.utilities.ros.RosTools; import us.ihmc.utilities.ros.subscriber.AbstractRosTopicSubscriber; diff --git a/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasZED2ROS1ToREABridge.java b/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasZED2ROS1ToREABridge.java index fa3b7f4e4d0..ab5d459c003 100644 --- a/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasZED2ROS1ToREABridge.java +++ b/atlas/src/main/java/us/ihmc/atlas/sensors/AtlasZED2ROS1ToREABridge.java @@ -19,7 +19,7 @@ import us.ihmc.commons.UnitConversions; import us.ihmc.tools.thread.MissingThreadTools; import us.ihmc.tools.thread.ResettableExceptionHandlingExecutorService; -import us.ihmc.tools.thread.Throttler; +import us.ihmc.commons.thread.Throttler; import us.ihmc.utilities.ros.RosMainNode; import us.ihmc.utilities.ros.RosTools; import us.ihmc.utilities.ros.subscriber.AbstractRosTopicSubscriber; diff --git a/ihmc-avatar-interfaces/src/main/java/us/ihmc/avatar/colorVision/stereo/DualBlackflyUDPReceiver.java b/ihmc-avatar-interfaces/src/main/java/us/ihmc/avatar/colorVision/stereo/DualBlackflyUDPReceiver.java index 1bf5e222a16..a8431cd8330 100644 --- a/ihmc-avatar-interfaces/src/main/java/us/ihmc/avatar/colorVision/stereo/DualBlackflyUDPReceiver.java +++ b/ihmc-avatar-interfaces/src/main/java/us/ihmc/avatar/colorVision/stereo/DualBlackflyUDPReceiver.java @@ -5,7 +5,7 @@ import us.ihmc.perception.ImageDimensions; import us.ihmc.robotics.robotSide.RobotSide; import us.ihmc.robotics.robotSide.SideDependentList; -import us.ihmc.tools.time.FrequencyCalculator; +import us.ihmc.commons.time.FrequencyCalculator; import java.io.IOException; import java.net.DatagramPacket; diff --git a/ihmc-communication/src/main/java/us/ihmc/communication/property/ROS2StoredPropertySet.java b/ihmc-communication/src/main/java/us/ihmc/communication/property/ROS2StoredPropertySet.java index fb2959dc9d2..6154cf51fac 100644 --- a/ihmc-communication/src/main/java/us/ihmc/communication/property/ROS2StoredPropertySet.java +++ b/ihmc-communication/src/main/java/us/ihmc/communication/property/ROS2StoredPropertySet.java @@ -2,7 +2,7 @@ import us.ihmc.communication.ros2.ROS2PublishSubscribeAPI; import us.ihmc.tools.property.StoredPropertySetBasics; -import us.ihmc.tools.thread.Throttler; +import us.ihmc.commons.thread.Throttler; /** * ROS 2 enabled, synced, interprocess stored property set. It allows external process diff --git a/ihmc-communication/src/main/java/us/ihmc/communication/ros2/ROS2Heartbeat.java b/ihmc-communication/src/main/java/us/ihmc/communication/ros2/ROS2Heartbeat.java index bfebf3db88e..53d01d4ec98 100644 --- a/ihmc-communication/src/main/java/us/ihmc/communication/ros2/ROS2Heartbeat.java +++ b/ihmc-communication/src/main/java/us/ihmc/communication/ros2/ROS2Heartbeat.java @@ -1,14 +1,14 @@ package us.ihmc.communication.ros2; import std_msgs.msg.dds.Empty; +import us.ihmc.commons.UnitConversions; import us.ihmc.commons.exception.DefaultExceptionHandler; import us.ihmc.commons.exception.ExceptionTools; import us.ihmc.commons.thread.ThreadTools; -import us.ihmc.ros2.ROS2PublisherBasics; +import us.ihmc.commons.thread.Throttler; import us.ihmc.ros2.ROS2NodeInterface; +import us.ihmc.ros2.ROS2PublisherBasics; import us.ihmc.ros2.ROS2Topic; -import us.ihmc.commons.UnitConversions; -import us.ihmc.tools.thread.Throttler; /** * Use this class to indicate to other things on the network that something is active. diff --git a/ihmc-communication/src/main/java/us/ihmc/communication/ros2/ROS2HeartbeatMonitor.java b/ihmc-communication/src/main/java/us/ihmc/communication/ros2/ROS2HeartbeatMonitor.java index 153a70f8569..beda24349c4 100644 --- a/ihmc-communication/src/main/java/us/ihmc/communication/ros2/ROS2HeartbeatMonitor.java +++ b/ihmc-communication/src/main/java/us/ihmc/communication/ros2/ROS2HeartbeatMonitor.java @@ -8,7 +8,7 @@ import us.ihmc.ros2.ROS2Input; import us.ihmc.ros2.ROS2Topic; import us.ihmc.tools.Timer; -import us.ihmc.tools.thread.Throttler; +import us.ihmc.commons.thread.Throttler; import java.util.function.Consumer; diff --git a/ihmc-communication/src/main/java/us/ihmc/communication/ros2/ROS2TunedRigidBodyTransform.java b/ihmc-communication/src/main/java/us/ihmc/communication/ros2/ROS2TunedRigidBodyTransform.java index 6bd6f913c03..a3e6701b57a 100644 --- a/ihmc-communication/src/main/java/us/ihmc/communication/ros2/ROS2TunedRigidBodyTransform.java +++ b/ihmc-communication/src/main/java/us/ihmc/communication/ros2/ROS2TunedRigidBodyTransform.java @@ -4,7 +4,7 @@ import us.ihmc.ros2.ROS2Input; import us.ihmc.communication.packets.MessageTools; import us.ihmc.euclid.transform.RigidBodyTransform; -import us.ihmc.tools.thread.Throttler; +import us.ihmc.commons.thread.Throttler; /** * This class is used to hava UI that tunes a transform running remotely on the robot. diff --git a/ihmc-graphics/src/libgdx/java/us/ihmc/rdx/imgui/GlfwWindowForImGui.java b/ihmc-graphics/src/libgdx/java/us/ihmc/rdx/imgui/GlfwWindowForImGui.java index 43af5025fb3..7754e88e178 100644 --- a/ihmc-graphics/src/libgdx/java/us/ihmc/rdx/imgui/GlfwWindowForImGui.java +++ b/ihmc-graphics/src/libgdx/java/us/ihmc/rdx/imgui/GlfwWindowForImGui.java @@ -11,7 +11,7 @@ import us.ihmc.commons.UnitConversions; import us.ihmc.tools.io.resources.ResourceTools; import us.ihmc.tools.processManagement.UnsignedByteTools; -import us.ihmc.tools.thread.Throttler; +import us.ihmc.commons.thread.Throttler; import javax.imageio.ImageIO; import java.awt.*; diff --git a/ihmc-graphics/src/libgdx/java/us/ihmc/rdx/imgui/ImGuiAveragedFrequencyText.java b/ihmc-graphics/src/libgdx/java/us/ihmc/rdx/imgui/ImGuiAveragedFrequencyText.java index e246c1f88c7..952b98f1e37 100644 --- a/ihmc-graphics/src/libgdx/java/us/ihmc/rdx/imgui/ImGuiAveragedFrequencyText.java +++ b/ihmc-graphics/src/libgdx/java/us/ihmc/rdx/imgui/ImGuiAveragedFrequencyText.java @@ -1,7 +1,7 @@ package us.ihmc.rdx.imgui; import imgui.internal.ImGui; -import us.ihmc.tools.time.FrequencyCalculator; +import us.ihmc.commons.time.FrequencyCalculator; public class ImGuiAveragedFrequencyText { diff --git a/ihmc-graphics/src/libgdx/java/us/ihmc/rdx/imgui/ImGuiFrequencyDisplay.java b/ihmc-graphics/src/libgdx/java/us/ihmc/rdx/imgui/ImGuiFrequencyDisplay.java index fcc97b91850..70c3cbfc8e8 100644 --- a/ihmc-graphics/src/libgdx/java/us/ihmc/rdx/imgui/ImGuiFrequencyDisplay.java +++ b/ihmc-graphics/src/libgdx/java/us/ihmc/rdx/imgui/ImGuiFrequencyDisplay.java @@ -1,6 +1,6 @@ package us.ihmc.rdx.imgui; -import us.ihmc.tools.time.FrequencyCalculator; +import us.ihmc.commons.time.FrequencyCalculator; /** * Call {@link #ping} at some frequency and optionally render a size 100 window diff --git a/ihmc-graphics/src/libgdx/java/us/ihmc/rdx/imgui/ImGuiGlfwWindow.java b/ihmc-graphics/src/libgdx/java/us/ihmc/rdx/imgui/ImGuiGlfwWindow.java index 151ba8752b7..779d8790e80 100644 --- a/ihmc-graphics/src/libgdx/java/us/ihmc/rdx/imgui/ImGuiGlfwWindow.java +++ b/ihmc-graphics/src/libgdx/java/us/ihmc/rdx/imgui/ImGuiGlfwWindow.java @@ -12,7 +12,7 @@ import us.ihmc.tools.io.HybridResourceDirectory; import us.ihmc.tools.io.HybridResourceFile; import us.ihmc.tools.io.JSONFileTools; -import us.ihmc.tools.time.FrequencyCalculator; +import us.ihmc.commons.time.FrequencyCalculator; import java.nio.file.Path; import java.nio.file.Paths; diff --git a/ihmc-graphics/src/libgdx/java/us/ihmc/rdx/imgui/ImPlotFrequencyPlot.java b/ihmc-graphics/src/libgdx/java/us/ihmc/rdx/imgui/ImPlotFrequencyPlot.java index 46be570ee13..1e079c2c054 100644 --- a/ihmc-graphics/src/libgdx/java/us/ihmc/rdx/imgui/ImPlotFrequencyPlot.java +++ b/ihmc-graphics/src/libgdx/java/us/ihmc/rdx/imgui/ImPlotFrequencyPlot.java @@ -1,6 +1,6 @@ package us.ihmc.rdx.imgui; -import us.ihmc.tools.time.FrequencyCalculator; +import us.ihmc.commons.time.FrequencyCalculator; public class ImPlotFrequencyPlot { diff --git a/ihmc-graphics/src/libgdx/java/us/ihmc/rdx/vr/RDXVRManager.java b/ihmc-graphics/src/libgdx/java/us/ihmc/rdx/vr/RDXVRManager.java index 7f8a16aa075..8e9c8fc9f23 100644 --- a/ihmc-graphics/src/libgdx/java/us/ihmc/rdx/vr/RDXVRManager.java +++ b/ihmc-graphics/src/libgdx/java/us/ihmc/rdx/vr/RDXVRManager.java @@ -19,12 +19,10 @@ import us.ihmc.rdx.ui.RDXBaseUI; import us.ihmc.rdx.ui.gizmo.RDXPose3DGizmo; import us.ihmc.robotics.robotSide.RobotSide; -import us.ihmc.tools.thread.MissingThreadTools; -import us.ihmc.tools.time.FrequencyCalculator; +import us.ihmc.commons.time.FrequencyCalculator; import java.util.ArrayList; import java.util.List; -import java.util.Set; import java.util.stream.Collectors; public class RDXVRManager @@ -101,7 +99,7 @@ private boolean pollEvents(RDXBaseUI baseUI) { initializing = true; contextCreatedNotification = new Notification(); - MissingThreadTools.startAsDaemon(getClass().getSimpleName() + "-initSystem", DefaultExceptionHandler.MESSAGE_AND_STACKTRACE, () -> + ThreadTools.startAsDaemon(() -> { synchronized (syncObject) { @@ -109,7 +107,7 @@ private boolean pollEvents(RDXBaseUI baseUI) context.initSystem(); } contextCreatedNotification.set(); - }); + }, DefaultExceptionHandler.MESSAGE_AND_STACKTRACE, getClass().getSimpleName() + "-initSystem"); } if (contextCreatedNotification != null && contextCreatedNotification.poll()) { diff --git a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/logging/FFMPEGLoggerDemoHelper.java b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/logging/FFMPEGLoggerDemoHelper.java index bd17face7d4..186b996e4c1 100644 --- a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/logging/FFMPEGLoggerDemoHelper.java +++ b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/logging/FFMPEGLoggerDemoHelper.java @@ -3,13 +3,13 @@ import imgui.ImGui; import imgui.type.ImInt; import us.ihmc.commons.FormattingTools; +import us.ihmc.commons.UnitConversions; import us.ihmc.commons.thread.ThreadTools; +import us.ihmc.commons.thread.Throttler; import us.ihmc.commons.time.Stopwatch; +import us.ihmc.log.LogTools; import us.ihmc.rdx.imgui.ImGuiUniqueLabelMap; import us.ihmc.rdx.imgui.ImPlotFrequencyPlot; -import us.ihmc.log.LogTools; -import us.ihmc.commons.UnitConversions; -import us.ihmc.tools.thread.Throttler; import java.io.File; import java.lang.reflect.Constructor; diff --git a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/logging/FFMPEGVideoPlaybackManager.java b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/logging/FFMPEGVideoPlaybackManager.java index c4dd8f18e0d..ca8df4fadf4 100644 --- a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/logging/FFMPEGVideoPlaybackManager.java +++ b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/logging/FFMPEGVideoPlaybackManager.java @@ -8,7 +8,7 @@ import us.ihmc.perception.BytedecoImage; import us.ihmc.perception.ffmpeg.FFmpegTools; import us.ihmc.perception.logging.PerceptionLoggerConstants; -import us.ihmc.tools.thread.Throttler; +import us.ihmc.commons.thread.Throttler; public class FFMPEGVideoPlaybackManager { diff --git a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/perception/RDXBlackflyCalibrationSuite.java b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/perception/RDXBlackflyCalibrationSuite.java index afd368aee73..3fb6a58d1d1 100644 --- a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/perception/RDXBlackflyCalibrationSuite.java +++ b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/perception/RDXBlackflyCalibrationSuite.java @@ -37,7 +37,7 @@ import us.ihmc.tools.thread.MissingThreadTools; import us.ihmc.tools.thread.ResettableExceptionHandlingExecutorService; import us.ihmc.tools.thread.SwapReference; -import us.ihmc.tools.thread.Throttler; +import us.ihmc.commons.thread.Throttler; import java.util.ArrayList; diff --git a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/perception/RDXCameraCalibrationDemo.java b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/perception/RDXCameraCalibrationDemo.java index 1e304658361..0108bc1ad87 100644 --- a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/perception/RDXCameraCalibrationDemo.java +++ b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/perception/RDXCameraCalibrationDemo.java @@ -22,7 +22,7 @@ import us.ihmc.rdx.imgui.ImPlotFrequencyPlot; import us.ihmc.rdx.imgui.ImPlotIntegerPlot; import us.ihmc.rdx.imgui.ImPlotStopwatchPlot; -import us.ihmc.tools.thread.Throttler; +import us.ihmc.commons.thread.Throttler; import java.io.File; import java.util.function.Consumer; diff --git a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/perception/RDXRealsenseD435UI.java b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/perception/RDXRealsenseD435UI.java index 7c8abbb0a5c..497a0c9ced5 100644 --- a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/perception/RDXRealsenseD435UI.java +++ b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/perception/RDXRealsenseD435UI.java @@ -13,7 +13,7 @@ import us.ihmc.rdx.imgui.ImGuiUniqueLabelMap; import us.ihmc.rdx.ui.RDXBaseUI; import us.ihmc.rdx.ui.interactable.RDXInteractableRealsenseD435; -import us.ihmc.tools.time.FrequencyCalculator; +import us.ihmc.commons.time.FrequencyCalculator; import us.ihmc.yoVariables.registry.YoRegistry; import java.nio.ByteOrder; diff --git a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/perception/RDXRealsenseL515UI.java b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/perception/RDXRealsenseL515UI.java index 4e14a757b0e..2adcc286227 100644 --- a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/perception/RDXRealsenseL515UI.java +++ b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/perception/RDXRealsenseL515UI.java @@ -28,7 +28,7 @@ import us.ihmc.rdx.sceneManager.RDXSceneLevel; import us.ihmc.rdx.ui.RDXBaseUI; import us.ihmc.rdx.ui.interactable.RDXInteractableRealsenseL515; -import us.ihmc.tools.time.FrequencyCalculator; +import us.ihmc.commons.time.FrequencyCalculator; import us.ihmc.yoVariables.registry.YoRegistry; import java.nio.ByteOrder; diff --git a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/perception/RDXWebcamROS2SubscriberDemo.java b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/perception/RDXWebcamROS2SubscriberDemo.java index 84480790f08..845f9b3dac6 100644 --- a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/perception/RDXWebcamROS2SubscriberDemo.java +++ b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/perception/RDXWebcamROS2SubscriberDemo.java @@ -20,7 +20,7 @@ import us.ihmc.rdx.imgui.ImPlotStopwatchPlot; import us.ihmc.robotics.time.TimeTools; import us.ihmc.ros2.RealtimeROS2Node; -import us.ihmc.tools.thread.Throttler; +import us.ihmc.commons.thread.Throttler; /** * Subscribes to ROS 2 webcam images with best performance. diff --git a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/perception/RDXZEDSVORecorderPanel.java b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/perception/RDXZEDSVORecorderPanel.java index 16560671770..b58ba07b592 100644 --- a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/perception/RDXZEDSVORecorderPanel.java +++ b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/perception/RDXZEDSVORecorderPanel.java @@ -10,7 +10,7 @@ import us.ihmc.rdx.imgui.ImGuiUniqueLabelMap; import us.ihmc.rdx.ui.RDXBaseUI; import us.ihmc.sensors.ZEDColorDepthImageRetrieverSVO.RecordMode; -import us.ihmc.tools.thread.Throttler; +import us.ihmc.commons.thread.Throttler; public class RDXZEDSVORecorderPanel { diff --git a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/simulation/sensors/RDXHighLevelDepthSensorSimulator.java b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/simulation/sensors/RDXHighLevelDepthSensorSimulator.java index 66ba0e884f6..72bfcde17b5 100644 --- a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/simulation/sensors/RDXHighLevelDepthSensorSimulator.java +++ b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/simulation/sensors/RDXHighLevelDepthSensorSimulator.java @@ -63,7 +63,7 @@ import us.ihmc.tools.string.StringTools; import us.ihmc.tools.thread.MissingThreadTools; import us.ihmc.tools.thread.ResettableExceptionHandlingExecutorService; -import us.ihmc.tools.thread.Throttler; +import us.ihmc.commons.thread.Throttler; import java.nio.ByteBuffer; import java.nio.ByteOrder; diff --git a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/affordances/RDXArmManager.java b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/affordances/RDXArmManager.java index ab5d609990d..1121a9a54e9 100644 --- a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/affordances/RDXArmManager.java +++ b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/affordances/RDXArmManager.java @@ -19,6 +19,7 @@ import us.ihmc.avatar.inverseKinematics.ArmIKSolver; import us.ihmc.behaviors.tools.CommunicationHelper; import us.ihmc.commons.exception.DefaultExceptionHandler; +import us.ihmc.commons.thread.ThreadTools; import us.ihmc.commons.thread.TypedNotification; import us.ihmc.communication.packets.MessageTools; import us.ihmc.euclid.referenceFrame.FramePose3D; @@ -35,7 +36,6 @@ import us.ihmc.robotics.partNames.ArmJointName; import us.ihmc.robotics.robotSide.RobotSide; import us.ihmc.robotics.robotSide.SideDependentList; -import us.ihmc.tools.thread.MissingThreadTools; import java.util.function.BooleanSupplier; @@ -182,7 +182,7 @@ public void update(boolean interactablesEnabled) armIKSolvers.get(side).copySourceToWork(); } - MissingThreadTools.startAThread("IKSolver", DefaultExceptionHandler.MESSAGE_AND_STACKTRACE, () -> + ThreadTools.startAThread(() -> { try { @@ -195,7 +195,7 @@ public void update(boolean interactablesEnabled) { readyToCopySolution = true; } - }); + }, DefaultExceptionHandler.MESSAGE_AND_STACKTRACE, "IKSolver"); } if (readyToCopySolution) diff --git a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/behavior/tree/RDXROS2BehaviorTree.java b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/behavior/tree/RDXROS2BehaviorTree.java index 4d3b6b372fc..2d1151aa8c6 100644 --- a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/behavior/tree/RDXROS2BehaviorTree.java +++ b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/behavior/tree/RDXROS2BehaviorTree.java @@ -12,7 +12,7 @@ import us.ihmc.robotics.physics.RobotCollisionModel; import us.ihmc.robotics.referenceFrames.ReferenceFrameLibrary; import us.ihmc.tools.io.WorkspaceResourceDirectory; -import us.ihmc.tools.thread.Throttler; +import us.ihmc.commons.thread.Throttler; /** * Top level class for the operator's behavior tree. diff --git a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/footstepPlanner/RDXFootstepPlanning.java b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/footstepPlanner/RDXFootstepPlanning.java index fcfd2dfb2b6..8c4f30cbb25 100644 --- a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/footstepPlanner/RDXFootstepPlanning.java +++ b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/footstepPlanner/RDXFootstepPlanning.java @@ -32,7 +32,7 @@ import us.ihmc.sensorProcessing.heightMap.HeightMapData; import us.ihmc.tools.thread.MissingThreadTools; import us.ihmc.tools.thread.ResettableExceptionHandlingExecutorService; -import us.ihmc.tools.thread.Throttler; +import us.ihmc.commons.thread.Throttler; import java.util.ArrayList; diff --git a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/graphics/RDXMessageSizeReadout.java b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/graphics/RDXMessageSizeReadout.java index 4d32260a69b..e8a9cf8a000 100644 --- a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/graphics/RDXMessageSizeReadout.java +++ b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/graphics/RDXMessageSizeReadout.java @@ -2,7 +2,7 @@ import imgui.internal.ImGui; import us.ihmc.commons.FormattingTools; -import us.ihmc.tools.thread.Throttler; +import us.ihmc.commons.thread.Throttler; /** * Keep track of the size of the incoming messages while slowing it down diff --git a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/graphics/ros2/RDXROS2BallTrackingVisualizer.java b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/graphics/ros2/RDXROS2BallTrackingVisualizer.java index 3c6561dd4a5..d2eb3ca240b 100644 --- a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/graphics/ros2/RDXROS2BallTrackingVisualizer.java +++ b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/graphics/ros2/RDXROS2BallTrackingVisualizer.java @@ -16,7 +16,6 @@ import us.ihmc.euclid.transform.RigidBodyTransform; import us.ihmc.pubsub.DomainFactory.PubSubImplementation; import us.ihmc.pubsub.subscriber.Subscriber; -import us.ihmc.rdx.imgui.ImGuiAveragedFrequencyText; import us.ihmc.rdx.imgui.ImGuiExpandCollapseRenderer; import us.ihmc.rdx.imgui.ImGuiTools; import us.ihmc.rdx.sceneManager.RDXSceneLevel; @@ -24,7 +23,7 @@ import us.ihmc.ros2.ROS2Topic; import us.ihmc.ros2.RealtimeROS2Node; import us.ihmc.tools.string.StringTools; -import us.ihmc.tools.thread.Throttler; +import us.ihmc.commons.thread.Throttler; import java.time.Instant; import java.util.Set; diff --git a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/graphics/ros2/RDXYOLOv8Settings.java b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/graphics/ros2/RDXYOLOv8Settings.java index 2ae960456b0..da566842b80 100644 --- a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/graphics/ros2/RDXYOLOv8Settings.java +++ b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/graphics/ros2/RDXYOLOv8Settings.java @@ -8,12 +8,8 @@ import us.ihmc.communication.PerceptionAPI; import us.ihmc.communication.ros2.ROS2Heartbeat; import us.ihmc.communication.ros2.ROS2PublishSubscribeAPI; -import us.ihmc.rdx.imgui.ImGuiTools; import us.ihmc.rdx.ui.graphics.RDXVisualizer; -import us.ihmc.tools.thread.Throttler; - -import java.util.Arrays; -import java.util.HashSet; +import us.ihmc.commons.thread.Throttler; /* * FIXME: It doesn't make sense to have a visualizer for settings. diff --git a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/interactable/RDXChestOrientationSlider.java b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/interactable/RDXChestOrientationSlider.java index bb2b5fd0128..f1fa036c881 100644 --- a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/interactable/RDXChestOrientationSlider.java +++ b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/interactable/RDXChestOrientationSlider.java @@ -6,17 +6,17 @@ import us.ihmc.avatar.drcRobot.ROS2SyncedRobotModel; import us.ihmc.avatar.ros2.ROS2ControllerHelper; import us.ihmc.commons.MathTools; +import us.ihmc.commons.UnitConversions; +import us.ihmc.commons.thread.Throttler; import us.ihmc.communication.packets.MessageTools; import us.ihmc.euclid.referenceFrame.FrameYawPitchRoll; import us.ihmc.euclid.referenceFrame.ReferenceFrame; import us.ihmc.euclid.tools.EuclidCoreTools; -import us.ihmc.rdx.imgui.ImGuiUniqueLabelMap; -import us.ihmc.rdx.ui.teleoperation.RDXTeleoperationParameters; import us.ihmc.humanoidRobotics.communication.packets.HumanoidMessageTools; import us.ihmc.log.LogTools; +import us.ihmc.rdx.imgui.ImGuiUniqueLabelMap; +import us.ihmc.rdx.ui.teleoperation.RDXTeleoperationParameters; import us.ihmc.robotics.geometry.YawPitchRollAxis; -import us.ihmc.commons.UnitConversions; -import us.ihmc.tools.thread.Throttler; public class RDXChestOrientationSlider { diff --git a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/interactable/RDXNeckPitchSlider.java b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/interactable/RDXNeckPitchSlider.java index 5c71c346e4f..2ac6e46290b 100644 --- a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/interactable/RDXNeckPitchSlider.java +++ b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/interactable/RDXNeckPitchSlider.java @@ -4,10 +4,10 @@ import imgui.internal.ImGui; import us.ihmc.avatar.drcRobot.ROS2SyncedRobotModel; import us.ihmc.avatar.ros2.ROS2ControllerHelper; +import us.ihmc.commons.UnitConversions; +import us.ihmc.commons.thread.Throttler; import us.ihmc.rdx.imgui.ImGuiUniqueLabelMap; import us.ihmc.rdx.ui.teleoperation.RDXTeleoperationParameters; -import us.ihmc.commons.UnitConversions; -import us.ihmc.tools.thread.Throttler; public class RDXNeckPitchSlider { diff --git a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/interactable/RDXPelvisHeightSlider.java b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/interactable/RDXPelvisHeightSlider.java index 9aca2ce7344..dc352edeae3 100644 --- a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/interactable/RDXPelvisHeightSlider.java +++ b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/interactable/RDXPelvisHeightSlider.java @@ -16,7 +16,7 @@ import us.ihmc.log.LogTools; import us.ihmc.commons.UnitConversions; import us.ihmc.tools.string.StringTools; -import us.ihmc.tools.thread.Throttler; +import us.ihmc.commons.thread.Throttler; public class RDXPelvisHeightSlider { diff --git a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/interactable/RDXSakeHandWidgets.java b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/interactable/RDXSakeHandWidgets.java index 5452a2ac6ce..82953416e17 100644 --- a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/interactable/RDXSakeHandWidgets.java +++ b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/interactable/RDXSakeHandWidgets.java @@ -8,7 +8,9 @@ import us.ihmc.avatar.sakeGripper.SakeHandParameters; import us.ihmc.avatar.sakeGripper.SakeHandPreset; import us.ihmc.behaviors.tools.CommunicationHelper; +import us.ihmc.commons.UnitConversions; import us.ihmc.commons.thread.Notification; +import us.ihmc.commons.thread.Throttler; import us.ihmc.communication.SakeHandAPI; import us.ihmc.log.LogTools; import us.ihmc.rdx.imgui.ImGuiFlashingText; @@ -19,8 +21,6 @@ import us.ihmc.robotics.EuclidCoreMissingTools; import us.ihmc.robotics.robotSide.RobotSide; import us.ihmc.tools.Timer; -import us.ihmc.commons.UnitConversions; -import us.ihmc.tools.thread.Throttler; public class RDXSakeHandWidgets { diff --git a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/teleoperation/RDXWholeBodyIKManager.java b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/teleoperation/RDXWholeBodyIKManager.java index 1528ea1c1a0..49739c83944 100644 --- a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/teleoperation/RDXWholeBodyIKManager.java +++ b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/teleoperation/RDXWholeBodyIKManager.java @@ -18,13 +18,13 @@ import us.ihmc.avatar.ros2.ROS2ControllerHelper; import us.ihmc.behaviors.tools.walkingController.ControllerStatusTracker; import us.ihmc.commons.exception.DefaultExceptionHandler; +import us.ihmc.commons.thread.ThreadTools; import us.ihmc.communication.packets.MessageTools; import us.ihmc.euclid.referenceFrame.FramePose3D; import us.ihmc.euclid.referenceFrame.ReferenceFrame; import us.ihmc.graphicsDescription.yoGraphics.YoGraphicsListRegistry; import us.ihmc.humanoidRobotics.communication.kinematicsToolboxAPI.KinematicsToolboxRigidBodyCommand; import us.ihmc.idl.IDLSequence.Object; -import us.ihmc.log.LogTools; import us.ihmc.mecano.multiBodySystem.interfaces.OneDoFJointBasics; import us.ihmc.rdx.imgui.ImGuiTools; import us.ihmc.rdx.imgui.ImGuiUniqueLabelMap; @@ -40,7 +40,6 @@ import us.ihmc.robotics.partNames.SpineJointName; import us.ihmc.robotics.robotSide.RobotSide; import us.ihmc.robotics.robotSide.SideDependentList; -import us.ihmc.tools.thread.MissingThreadTools; import us.ihmc.yoVariables.registry.YoRegistry; /** @@ -198,7 +197,7 @@ public void update() } // We solve on a thread because the solver can take some milliseconds - MissingThreadTools.startAThread(getClass().getSimpleName(), DefaultExceptionHandler.MESSAGE_AND_STACKTRACE, () -> + ThreadTools.startAThread(() -> { try { @@ -208,7 +207,7 @@ public void update() { readyToCopySolution = true; } - }); + }, DefaultExceptionHandler.MESSAGE_AND_STACKTRACE, getClass().getSimpleName()); } } diff --git a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/vr/RDXVRKinematicsStreamingMode.java b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/vr/RDXVRKinematicsStreamingMode.java index afbbcea3ce0..a8b7ae9b88f 100644 --- a/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/vr/RDXVRKinematicsStreamingMode.java +++ b/ihmc-high-level-behaviors/src/libgdx/java/us/ihmc/rdx/ui/vr/RDXVRKinematicsStreamingMode.java @@ -6,14 +6,22 @@ import imgui.ImGui; import imgui.type.ImBoolean; import org.lwjgl.openvr.InputDigitalActionData; -import toolbox_msgs.msg.dds.*; +import toolbox_msgs.msg.dds.KinematicsStreamingToolboxInputMessage; +import toolbox_msgs.msg.dds.KinematicsToolboxCenterOfMassMessage; +import toolbox_msgs.msg.dds.KinematicsToolboxConfigurationMessage; +import toolbox_msgs.msg.dds.KinematicsToolboxInitialConfigurationMessage; +import toolbox_msgs.msg.dds.KinematicsToolboxOutputStatus; +import toolbox_msgs.msg.dds.KinematicsToolboxRigidBodyMessage; +import toolbox_msgs.msg.dds.ToolboxStateMessage; import us.ihmc.avatar.drcRobot.DRCRobotModel; import us.ihmc.avatar.drcRobot.ROS2SyncedRobotModel; import us.ihmc.avatar.networkProcessor.kinemtaticsStreamingToolboxModule.KinematicsStreamingToolboxModule; import us.ihmc.avatar.networkProcessor.kinemtaticsStreamingToolboxModule.KinematicsStreamingToolboxParameters; import us.ihmc.avatar.ros2.ROS2ControllerHelper; import us.ihmc.behaviors.tools.walkingController.ControllerStatusTracker; +import us.ihmc.commons.UnitConversions; import us.ihmc.commons.thread.Notification; +import us.ihmc.commons.thread.Throttler; import us.ihmc.communication.OldHandAPI; import us.ihmc.communication.packets.MessageTools; import us.ihmc.communication.packets.ToolboxState; @@ -57,11 +65,15 @@ import us.ihmc.scs2.definition.robot.RobotDefinition; import us.ihmc.scs2.definition.visual.ColorDefinitions; import us.ihmc.scs2.definition.visual.MaterialDefinition; -import us.ihmc.commons.UnitConversions; -import us.ihmc.tools.thread.Throttler; import javax.annotation.Nullable; -import java.util.*; +import java.util.Arrays; +import java.util.HashMap; +import java.util.HashSet; +import java.util.LinkedHashMap; +import java.util.List; +import java.util.Map; +import java.util.Set; import static us.ihmc.communication.packets.MessageTools.toFrameId; import static us.ihmc.motionRetargeting.VRTrackedSegmentType.*; diff --git a/ihmc-high-level-behaviors/src/main/java/us/ihmc/behaviors/ai2r/AI2RNodeExecutor.java b/ihmc-high-level-behaviors/src/main/java/us/ihmc/behaviors/ai2r/AI2RNodeExecutor.java index 18c674ea6dd..ffa0d397990 100644 --- a/ihmc-high-level-behaviors/src/main/java/us/ihmc/behaviors/ai2r/AI2RNodeExecutor.java +++ b/ihmc-high-level-behaviors/src/main/java/us/ihmc/behaviors/ai2r/AI2RNodeExecutor.java @@ -13,7 +13,7 @@ import us.ihmc.perception.sceneGraph.SceneNode; import us.ihmc.tools.io.WorkspaceResourceDirectory; import us.ihmc.tools.io.resources.ResourceTools; -import us.ihmc.tools.thread.Throttler; +import us.ihmc.commons.thread.Throttler; /** * For interfacing with external foundation models. diff --git a/ihmc-high-level-behaviors/src/main/java/us/ihmc/behaviors/sequence/actions/FootstepPlanActionExecutor.java b/ihmc-high-level-behaviors/src/main/java/us/ihmc/behaviors/sequence/actions/FootstepPlanActionExecutor.java index 6df8735c39d..8c795fc2d72 100644 --- a/ihmc-high-level-behaviors/src/main/java/us/ihmc/behaviors/sequence/actions/FootstepPlanActionExecutor.java +++ b/ihmc-high-level-behaviors/src/main/java/us/ihmc/behaviors/sequence/actions/FootstepPlanActionExecutor.java @@ -27,7 +27,7 @@ import us.ihmc.robotics.robotSide.RobotSide; import us.ihmc.robotics.robotSide.SideDependentList; import us.ihmc.tools.io.WorkspaceResourceDirectory; -import us.ihmc.tools.thread.Throttler; +import us.ihmc.commons.thread.Throttler; import java.util.UUID; diff --git a/ihmc-high-level-behaviors/src/main/java/us/ihmc/behaviors/tools/walkingController/ControllerStatusTracker.java b/ihmc-high-level-behaviors/src/main/java/us/ihmc/behaviors/tools/walkingController/ControllerStatusTracker.java index 173081b34fc..3865f124389 100644 --- a/ihmc-high-level-behaviors/src/main/java/us/ihmc/behaviors/tools/walkingController/ControllerStatusTracker.java +++ b/ihmc-high-level-behaviors/src/main/java/us/ihmc/behaviors/tools/walkingController/ControllerStatusTracker.java @@ -12,7 +12,7 @@ import us.ihmc.humanoidRobotics.communication.packets.dataobjects.HighLevelControllerName; import us.ihmc.humanoidRobotics.communication.packets.walking.WalkingStatus; import us.ihmc.ros2.ROS2NodeInterface; -import us.ihmc.tools.thread.Throttler; +import us.ihmc.commons.thread.Throttler; import java.util.ArrayList; import java.util.List; diff --git a/ihmc-high-level-behaviors/src/test/java/us/ihmc/rdx/ui/ImPlotPlotDemo.java b/ihmc-high-level-behaviors/src/test/java/us/ihmc/rdx/ui/ImPlotPlotDemo.java index 96d389d886f..ab16a545416 100644 --- a/ihmc-high-level-behaviors/src/test/java/us/ihmc/rdx/ui/ImPlotPlotDemo.java +++ b/ihmc-high-level-behaviors/src/test/java/us/ihmc/rdx/ui/ImPlotPlotDemo.java @@ -7,7 +7,7 @@ import us.ihmc.rdx.imgui.ImPlotPlot; import us.ihmc.rdx.imgui.ImPlotDoublePlotLine; import us.ihmc.rdx.imgui.ImPlotPlotPanel; -import us.ihmc.tools.time.FrequencyCalculator; +import us.ihmc.commons.time.FrequencyCalculator; import java.util.Random; diff --git a/ihmc-java-toolkit/src/main/java/us/ihmc/tools/Timer.java b/ihmc-java-toolkit/src/main/java/us/ihmc/tools/Timer.java index 1e6733d35ee..15e332f5124 100644 --- a/ihmc-java-toolkit/src/main/java/us/ihmc/tools/Timer.java +++ b/ihmc-java-toolkit/src/main/java/us/ihmc/tools/Timer.java @@ -1,7 +1,7 @@ package us.ihmc.tools; import us.ihmc.commons.Conversions; -import us.ihmc.tools.thread.MissingThreadTools; +import us.ihmc.commons.thread.ThreadTools; public class Timer { @@ -35,7 +35,7 @@ public void sleepUntilExpiration(double expirationDuration) double expirationTime = resetTime + expirationDuration; double remainingDuration = expirationTime - Conversions.nanosecondsToSeconds(System.nanoTime()); - MissingThreadTools.sleepAtLeast(remainingDuration); + ThreadTools.parkAtLeast(remainingDuration); } } diff --git a/ihmc-java-toolkit/src/main/java/us/ihmc/tools/thread/MissingThreadTools.java b/ihmc-java-toolkit/src/main/java/us/ihmc/tools/thread/MissingThreadTools.java index 869f23a63ce..51730eb824d 100644 --- a/ihmc-java-toolkit/src/main/java/us/ihmc/tools/thread/MissingThreadTools.java +++ b/ihmc-java-toolkit/src/main/java/us/ihmc/tools/thread/MissingThreadTools.java @@ -1,82 +1,17 @@ package us.ihmc.tools.thread; import us.ihmc.commons.Conversions; -import us.ihmc.commons.RunnableThatThrows; -import us.ihmc.commons.exception.DefaultExceptionHandler; -import us.ihmc.commons.exception.ExceptionHandler; -import us.ihmc.commons.exception.ExceptionTools; import us.ihmc.commons.thread.ThreadTools; +import us.ihmc.commons.thread.Throttler; -import java.util.concurrent.*; +import java.util.concurrent.ArrayBlockingQueue; +import java.util.concurrent.LinkedBlockingQueue; +import java.util.concurrent.ThreadPoolExecutor; +import java.util.concurrent.TimeUnit; import java.util.concurrent.locks.LockSupport; public class MissingThreadTools { - /** - * Guarantees a sleep of a minimum duration in floating point seconds - * using {@link LockSupport#parkNanos}. It will always sleep a little too long. - * The amount overslept probably varies by system, but it has been observed to - * be less than half a millisecond. - * - * {@link ThreadTools#sleepSeconds} can actually return early because it - * cuts off the subnanosecond part, allowing it to undersleep by a nanosecond - * at most. - * - * @param duration to sleep in seconds - * @return Exactly how long it actually slept in seconds - */ - public static double sleepAtLeast(double duration) - { - double startTime = Conversions.nanosecondsToSeconds(System.nanoTime()); - double amountSlept = 0.0; - do - { - double nextDuration = duration - amountSlept; - - sleep(nextDuration); - - amountSlept = Conversions.nanosecondsToSeconds(System.nanoTime()) - startTime; - } - while (amountSlept < duration); - return amountSlept; - } - - /** - * Uses {@link LockSupport#parkNanos} to sleep for floating point seconds. - * {@link LockSupport#parkNanos} is more accurate than {@link Thread#sleep}. - * The requested sleep is guaranteed to be at least as long as the requested - * amount and can be up to a nanosecond longer. - */ - public static void sleep(double seconds) - { - double floatingNanos = seconds * 1e9; - long nanoseconds = (long) floatingNanos; - - if (floatingNanos > nanoseconds) // Take nanosecond ceiling instead of floor - ++nanoseconds; - - LockSupport.parkNanos(nanoseconds); // More accurate than Thread.sleep - } - - public static void sleepMillis(int millis) - { - try - { - Thread.sleep(millis); - } - catch (InterruptedException interruptedException) - { - // Ignore - } - } - - public static ThreadFactory createNamedThreadFactory(String prefix, boolean daemon) - { - boolean includePoolInName = true; - boolean includeThreadNumberInName = true; - return ThreadTools.createNamedThreadFactory(prefix, includePoolInName, includeThreadNumberInName, daemon, Thread.NORM_PRIORITY); - } - public static ResettableExceptionHandlingExecutorService newSingleThreadExecutor(String prefix) { return newSingleThreadExecutor(prefix, false); @@ -101,31 +36,8 @@ public static ResettableExceptionHandlingExecutorService newSingleThreadExecutor keepAliveTime, TimeUnit.MILLISECONDS, queueSize < 0 ? new LinkedBlockingQueue<>() : new ArrayBlockingQueue<>(queueSize), - createNamedThreadFactory(prefix, daemon), + ThreadTools.createNamedThreadFactory(prefix, daemon), new ThreadPoolExecutor.AbortPolicy()) ); } - - public static Thread startAsDaemon(String threadName, ExceptionHandler exceptionHandler, RunnableThatThrows runnable) - { - return ThreadTools.startAsDaemon(() -> ExceptionTools.handle(runnable, exceptionHandler), threadName); - - } - public static Thread startAsDaemon(String threadName, double period, RunnableThatThrows runnable) - { - Throttler throttler = new Throttler(); - return startAsDaemon(threadName, DefaultExceptionHandler.MESSAGE_AND_STACKTRACE, () -> - { - while (true) - { - throttler.waitAndRun(period); - runnable.run(); - } - }); - } - - public static Thread startAThread(String threadName, ExceptionHandler exceptionHandler, RunnableThatThrows runnable) - { - return ThreadTools.startAThread(() -> ExceptionTools.handle(runnable, exceptionHandler), threadName); - } } diff --git a/ihmc-java-toolkit/src/main/java/us/ihmc/tools/thread/RestartableThread.java b/ihmc-java-toolkit/src/main/java/us/ihmc/tools/thread/RestartableThread.java index cb75cc83852..bafc911259b 100644 --- a/ihmc-java-toolkit/src/main/java/us/ihmc/tools/thread/RestartableThread.java +++ b/ihmc-java-toolkit/src/main/java/us/ihmc/tools/thread/RestartableThread.java @@ -7,6 +7,10 @@ import java.util.concurrent.atomic.AtomicBoolean; +/** + * @deprecated Use {@link us.ihmc.commons.thread.RepeatingTaskThread} instead. + */ +@Deprecated public class RestartableThread { private final String name; @@ -94,9 +98,4 @@ public boolean isRunning() { return running.getPlain(); } - - boolean isAlive() - { - return thread == null ? false : thread.isAlive(); - } } diff --git a/ihmc-java-toolkit/src/main/java/us/ihmc/tools/thread/RestartableThrottledThread.java b/ihmc-java-toolkit/src/main/java/us/ihmc/tools/thread/RestartableThrottledThread.java index 336f2ea19e9..d264476c8fd 100644 --- a/ihmc-java-toolkit/src/main/java/us/ihmc/tools/thread/RestartableThrottledThread.java +++ b/ihmc-java-toolkit/src/main/java/us/ihmc/tools/thread/RestartableThrottledThread.java @@ -4,9 +4,13 @@ import us.ihmc.commons.exception.DefaultExceptionHandler; import us.ihmc.commons.exception.ExceptionHandler; import us.ihmc.commons.exception.ExceptionTools; +import us.ihmc.commons.thread.Throttler; import java.util.concurrent.atomic.AtomicBoolean; +/** + * @deprecated Use {@link us.ihmc.commons.thread.RepeatingTaskThread} with a frequency limit set. + */ public class RestartableThrottledThread { private final String name; @@ -89,10 +93,4 @@ public boolean isRunning() { return running.getPlain(); } - - // only used for testing - boolean isAlive() - { - return thread == null ? false : thread.isAlive(); - } } diff --git a/ihmc-java-toolkit/src/main/java/us/ihmc/tools/thread/Throttler.java b/ihmc-java-toolkit/src/main/java/us/ihmc/tools/thread/Throttler.java deleted file mode 100644 index a95d5b8765a..00000000000 --- a/ihmc-java-toolkit/src/main/java/us/ihmc/tools/thread/Throttler.java +++ /dev/null @@ -1,171 +0,0 @@ -package us.ihmc.tools.thread; - -import us.ihmc.commons.Conversions; - -/** - * Throttler is used to allow things to happen at a slower rate - * than the parent update thread. It features a run method, - * which returns whether or not enough time has passed to run something. - * Alternatively, it features a waitAndRun method, which allows the - * user to sleep until it is ready for the next thing. - * - * This class is useful as an alternative to creating additional - * threads when appropriate. It does not create any threads so - * there are no concurrency issues. - * - * Throttler's {@link #run} methods work best when polled at much higher frequencies - * than the requested throttled frequency. We have put a mechanism in place - * to handle poll frequencies near or lower than requested, but the result - * will be jittery and inaccurate. In those cases, it is best to spin - * up a separate thread. See {@link RestartableThrottledThread}. - * - * Throttler's {@link #waitAndRun} methods have a different nature. They - * obviously cannot be called faster than the requested frequency. They - * are designed to handle waiting the extra time after variable amounts - * of computation in order to run that computation at a steady rate. - * - * Example: - * - *
- * Throttler throttler = new Throttler().setFrequency(5.0); - * - * while (true) - * { - * if (throttler.run()) - * { - * // do stuff - * } - * } - *- */ -public class Throttler -{ - private double resetTime = Double.NaN; - private double optionallySetPeriod = Double.NaN; - private transient double currentTime; - private transient double overtime; - - /** - * Set the period. - * - * Syntactic sugar to be clear about what a constant passed in would be. - * For example, as a field: - * - *
- * private final Throttler throttler = new Throttler().setPeriod(5.0); - *- */ - public Throttler setPeriod(double period) - { - optionallySetPeriod = period; - return this; - } - - /** - * Set the frequency. - * - * Syntactic sugar to be clear about what a constant passed in would be. - * For example, as a field: - * - *
- * private final Throttler throttler = new Throttler().setFrequency(5.0); - *- */ - public Throttler setFrequency(double frequency) - { - optionallySetPeriod = Conversions.hertzToSeconds(frequency); - return this; - } - - /** - * @return Whether or not enough time has passed to run your thing again. - * It is recommended to call this at several times the desired throttled rate. - * Calling this more often is directly propotional to the resulting accuracy. - * - * For use if the user set the period with the {@link #setPeriod} method. - */ - public boolean run() - { - return run(optionallySetPeriod); - } - - /** - * @param period for passing in dynamically calculated periods - * @return Whether or not enough time has passed to run your thing again. - * It is recommended to call this at several times the desired throttled rate. - * Calling this more often is directly propotional to the resulting accuracy. - */ - public boolean run(double period) - { - currentTime = Conversions.nanosecondsToSeconds(System.nanoTime()); - - if (Double.isNaN(resetTime)) // First run - { - resetTime = currentTime; - return true; - } - else - { - calculateOvertime(period); - - boolean periodHasElapsed = overtime >= 0.0; - - if (periodHasElapsed) - { - // We subtract the overtime to achieve a more accurate rate - resetTime = currentTime - overtime; - } - - return periodHasElapsed; - } - } - - /** - * Sleeps until enough time has passed to run your thing again. - * - * For use if the user set the period with the {@link #setPeriod} method. - */ - public void waitAndRun() - { - waitAndRun(optionallySetPeriod); - } - - /** - * Sleeps until enough time has passed to run your thing again. - * - * @param period for passing in dynamically calculated periods - */ - public void waitAndRun(double period) - { - currentTime = Conversions.nanosecondsToSeconds(System.nanoTime()); - - if (Double.isNaN(resetTime)) // First run - { - resetTime = currentTime; - } - else - { - calculateOvertime(period); - - if (overtime < 0.0) - { - // Guarantees to sleep at least this amount (i.e. will sleep too long) - currentTime += MissingThreadTools.sleepAtLeast(-overtime); - - calculateOvertime(period); - } - - // We subtract the overtime to achieve a more accurate rate - resetTime = currentTime - overtime; - } - } - - private void calculateOvertime(double period) - { - double elapsedTime = currentTime - resetTime; - - // Limit the overtime to half the period, to prevent building up - // when the run methods are called too infrequently. - overtime = Math.min(elapsedTime - period, 0.5 * period); - } -} diff --git a/ihmc-java-toolkit/src/main/java/us/ihmc/tools/time/FrequencyCalculator.java b/ihmc-java-toolkit/src/main/java/us/ihmc/tools/time/FrequencyCalculator.java deleted file mode 100644 index 27dc6275938..00000000000 --- a/ihmc-java-toolkit/src/main/java/us/ihmc/tools/time/FrequencyCalculator.java +++ /dev/null @@ -1,110 +0,0 @@ -package us.ihmc.tools.time; - -import us.ihmc.commons.Conversions; -import us.ihmc.commons.thread.ThreadTools; -import us.ihmc.log.LogTools; -import us.ihmc.tools.thread.MissingThreadTools; - -import java.util.UUID; - -/** - * An exponential smoothing frequency calculator with an optional logging thread to print the frequency once per second. - * ... - * Call {@link #ping()} on each new event. - * Call {@link #getFrequency()} to get the frequency, which will remain constant if events stop. - * Call {@link #getFrequencyDecaying()} to get the current frequency which trends to 0 when there are no events. - */ -public class FrequencyCalculator -{ - private double alpha = 0.3; - private double lastEventTime = Double.NaN; - private double smoothedPeriod = Double.NaN; - - private volatile boolean loggingThreadRunning; - - public FrequencyCalculator(boolean enableLoggingThread) - { - if (enableLoggingThread) - { - String threadID = UUID.randomUUID().toString().substring(0, 5); - - Thread loggingThread = new Thread(() -> - { - loggingThreadRunning = true; - - while (loggingThreadRunning) - { - LogTools.info("FrequencyCalculator[" + threadID + "] average rate: " + getFrequency()); - - MissingThreadTools.sleep(1.0); - } - }, getClass().getSimpleName() + "-" + threadID); - - loggingThread.start(); - } - } - - public FrequencyCalculator() - { - this(false); - } - - private double calculateFrequency(boolean decay) - { - if (Double.isNaN(smoothedPeriod)) - { - return 0.0; - } - else - { - double currentTime = Conversions.nanosecondsToSeconds(System.nanoTime()); - double ongoingPeriod = currentTime - lastEventTime; - - if (!decay || ongoingPeriod < smoothedPeriod) // Expecting an event after the current average period - { - return 1.0 / smoothedPeriod; - } - else // Events are slowing down or stopped - { - double psuedoSmoothedPeriod = (1.0 - alpha) * smoothedPeriod + alpha * ongoingPeriod; - return 1.0 / psuedoSmoothedPeriod; - } - } - } - - public void ping() - { - double currentTime = Conversions.nanosecondsToSeconds(System.nanoTime()); - - if (!Double.isNaN(lastEventTime)) - { - double period = currentTime - lastEventTime; - - if (Double.isNaN(smoothedPeriod)) - { - smoothedPeriod = period; - } - else - { - smoothedPeriod = (1.0 - alpha) * smoothedPeriod + alpha * period; - } - } - - lastEventTime = currentTime; - } - - public double getFrequency() - { - return calculateFrequency(false); - } - - public double getFrequencyDecaying() - { - return calculateFrequency(true); - } - - public void destroy() - { - loggingThreadRunning = false; - } -} diff --git a/ihmc-java-toolkit/src/main/java/us/ihmc/tools/time/FrequencyStatisticPrinter.java b/ihmc-java-toolkit/src/main/java/us/ihmc/tools/time/FrequencyStatisticPrinter.java index 8a887d09e45..8f881bcd680 100644 --- a/ihmc-java-toolkit/src/main/java/us/ihmc/tools/time/FrequencyStatisticPrinter.java +++ b/ihmc-java-toolkit/src/main/java/us/ihmc/tools/time/FrequencyStatisticPrinter.java @@ -1,5 +1,6 @@ package us.ihmc.tools.time; +import us.ihmc.commons.time.FrequencyCalculator; import us.ihmc.commons.time.Stopwatch; import us.ihmc.log.LogTools; import us.ihmc.tools.Timer; diff --git a/ihmc-java-toolkit/src/test/java/us/ihmc/tools/TimerTest.java b/ihmc-java-toolkit/src/test/java/us/ihmc/tools/TimerTest.java index b224f738e3b..e6940a63d9d 100644 --- a/ihmc-java-toolkit/src/test/java/us/ihmc/tools/TimerTest.java +++ b/ihmc-java-toolkit/src/test/java/us/ihmc/tools/TimerTest.java @@ -2,8 +2,8 @@ import org.junit.jupiter.api.Test; import us.ihmc.commons.Conversions; +import us.ihmc.commons.thread.ThreadTools; import us.ihmc.log.LogTools; -import us.ihmc.tools.thread.MissingThreadTools; import static org.junit.jupiter.api.Assertions.*; @@ -56,7 +56,7 @@ private static void testTimer(double expirationTime) assertTrue(timer.isRunning(expirationTime)); assertFalse(timer.isExpired(expirationTime)); - MissingThreadTools.sleepAtLeast(expirationTime); + ThreadTools.parkAtLeast(expirationTime); assertFalse(timer.isRunning(expirationTime)); assertTrue(timer.isExpired(expirationTime)); diff --git a/ihmc-java-toolkit/src/test/java/us/ihmc/tools/thread/MissingThreadToolsTest.java b/ihmc-java-toolkit/src/test/java/us/ihmc/tools/thread/MissingThreadToolsTest.java index 4eb4e5f9720..ba1ce7ef726 100644 --- a/ihmc-java-toolkit/src/test/java/us/ihmc/tools/thread/MissingThreadToolsTest.java +++ b/ihmc-java-toolkit/src/test/java/us/ihmc/tools/thread/MissingThreadToolsTest.java @@ -2,16 +2,10 @@ import gnu.trove.list.array.TIntArrayList; import org.junit.jupiter.api.Test; -import us.ihmc.commons.Conversions; -import us.ihmc.commons.exception.DefaultExceptionHandler; -import us.ihmc.commons.exception.ExceptionTools; import us.ihmc.commons.thread.ThreadTools; import us.ihmc.commons.thread.TypedNotification; import us.ihmc.log.LogTools; -import java.util.concurrent.ScheduledExecutorService; -import java.util.concurrent.ScheduledFuture; -import java.util.concurrent.TimeUnit; import java.util.concurrent.atomic.AtomicInteger; import static org.junit.jupiter.api.Assertions.*; @@ -19,48 +13,6 @@ public class MissingThreadToolsTest { - @Test - public void testSleepAtLeast() - { - assertTrue(conductSleepTest(0.0000000000001, false)); - assertTrue(conductSleepTest(0.5e-9, false)); - assertTrue(conductSleepTest(1e-9, false)); - assertTrue(conductSleepTest(0.1, false)); - assertTrue(conductSleepTest(0.0001, false)); - assertTrue(conductSleepTest(0.0000000005, false)); - assertTrue(conductSleepTest(1.1, false)); - assertTrue(conductSleepTest(2.0, false)); - - assertTrue(conductSleepTest(0.0000000000001, true)); - assertTrue(conductSleepTest(0.5e-9, true)); - assertTrue(conductSleepTest(1e-9, true)); - assertTrue(conductSleepTest(0.1, true)); - assertTrue(conductSleepTest(0.0001, true)); - assertTrue(conductSleepTest(0.0000000005, true)); - assertTrue(conductSleepTest(1.1, true)); - assertTrue(conductSleepTest(2.0, true)); - } - - private boolean conductSleepTest(double sleepDuration, boolean atLeast) - { - double before = Conversions.nanosecondsToSeconds(System.nanoTime()); - - if (atLeast) - MissingThreadTools.sleepAtLeast(sleepDuration); - else - MissingThreadTools.sleep(sleepDuration); - - double after = Conversions.nanosecondsToSeconds(System.nanoTime()); - - double overslept = (after - before) - sleepDuration; - - LogTools.info("Overslept %f ms".formatted(Conversions.secondsToMilliseconds(overslept))); - - assertTrue(overslept < 0.005); // Assert we don't oversleep more than 5 milliseconds -- typically a lot lower - - return overslept > 0.0; - } - @Test public void testSecondsDecomposition() { @@ -111,7 +63,7 @@ public void testSingleScheduleThreadWithThrownException() AtomicInteger numberOfThingsThatHappened = new AtomicInteger(); executor.execute(() -> { - MissingThreadTools.sleepAtLeast(0.01); + ThreadTools.parkAtLeast(0.01); ints.add(0); LogTools.info("ints = {}", ints); @@ -126,7 +78,7 @@ public void testSingleScheduleThreadWithThrownException() executor.submit(() -> { - MissingThreadTools.sleepAtLeast(0.01); + ThreadTools.parkAtLeast(0.01); ints.add(1); LogTools.info("ints = {}", ints); @@ -141,7 +93,7 @@ public void testSingleScheduleThreadWithThrownException() executor.submit(() -> { - MissingThreadTools.sleepAtLeast(0.01); + ThreadTools.parkAtLeast(0.01); ints.add(2); LogTools.info("ints = {}", ints); @@ -158,7 +110,7 @@ public void testSingleScheduleThreadWithThrownException() executor.submit(() -> { - MissingThreadTools.sleepAtLeast(0.01); + ThreadTools.parkAtLeast(0.01); ints.add(3); LogTools.info("ints = {}", ints); @@ -183,7 +135,7 @@ private static void awaitExecution(ResettableExceptionHandlingExecutorService ex double timeout = 2.0; while (executor.isExecuting() && timeSlept < timeout) { - timeSlept += MissingThreadTools.sleepAtLeast(0.2); + timeSlept += ThreadTools.parkAtLeast(0.2); } assertTrue(timeSlept < timeout, "Timed out"); @@ -267,41 +219,4 @@ public void testSkipItemInQueue() executor.destroy(); } - - @Test - public void testCancellableScheduledTasks() - { - ScheduledExecutorService scheduler = ThreadTools.newSingleDaemonThreadScheduledExecutor("Test"); - - StringBuilder output = new StringBuilder(); - - ScheduledFuture> scheduledFuture1 = scheduler.schedule(() -> output.append("A"), 400, TimeUnit.MILLISECONDS); - ThreadTools.sleep(200); - scheduledFuture1.cancel(false); - scheduler.schedule(() -> output.append("B"), 400, TimeUnit.MILLISECONDS); - ThreadTools.sleep(600); - ScheduledFuture