41#include <gmock/gmock.h>
42#include <gtest/gtest.h>
46#include <rclcpp/rclcpp.hpp>
47#include <tf2_ros/buffer.h>
49using namespace std::chrono_literals;
73void waitFor(std::chrono::seconds timeout,
const std::function<
bool()>& done)
75 const auto start = std::chrono::steady_clock::now();
76 while ((std::chrono::steady_clock::now() - start) < timeout)
82 std::this_thread::sleep_for(1ms);
86TEST(TrajectoryMonitorTests, SleepAtLeastOnce)
88 auto mock_trajectory_monitor_middleware_handle = std::make_unique<MockTrajectoryMonitorMiddlewareHandle>();
89 auto mock_current_state_monitor_middleware_handle = std::make_unique<MockCurrentStateMonitorMiddlewareHandle>();
92 EXPECT_CALL(*mock_trajectory_monitor_middleware_handle, sleep).Times(::testing::AtLeast(1));
95 auto current_state_monitor = std::make_shared<planning_scene_monitor::CurrentStateMonitor>(
97 std::make_shared<tf2_ros::Buffer>(std::make_shared<rclcpp::Clock>()),
false);
100 std::move(mock_trajectory_monitor_middleware_handle),
104 std::atomic<bool> callback_called{
false };
106 const rclcpp::Time& ) { callback_called =
true; });
109 trajectory_monitor.startTrajectoryMonitor();
110 waitFor(10s, [&]() {
return static_cast<bool>(callback_called); });
115 ::testing::InitGoogleTest(&argc, argv);
116 return RUN_ALL_TESTS();
Dependency injection class for testing the CurrentStateMonitor.
virtual std::string getJointStateTopicName() const =0
Get the joint state topic name.
virtual void createStaticTfSubscription(TfCallback callback)=0
Creates a static transform message subscription.
virtual void resetTfSubscriptions()=0
Reset the static & dynamic transform subscriptions.
virtual void resetJointStateSubscription()=0
Reset the joint state subscription.
virtual bool sleepFor(const std::chrono::nanoseconds &nanoseconds) const =0
Block for the specified amount of time.
virtual void createJointStateSubscription(const std::string &topic, JointStateUpdateCallback callback)=0
Creates a joint state subscription.
std::function< void(const tf2_msgs::msg::TFMessage::ConstSharedPtr)> TfCallback
virtual std::string getDynamicTfTopicName() const =0
Get the dynamic transform topic name.
virtual rclcpp::Time now() const =0
Get the current time.
virtual void createDynamicTfSubscription(TfCallback callback)=0
Creates a dynamic transform message subscription.
virtual bool ok() const =0
Uses rclcpp::ok to check the context status.
virtual std::string getStaticTfTopicName() const =0
Get the static transform topic name.
This class contains the rcl interfaces for easier testing.
virtual void sleep()=0
Sleep the handle for some prescribed amount of time.
virtual void setRate(double sampling_frequency)=0
set Rate using sampling frequency
Monitors the joint_states topic and tf to record the trajectory of the robot.
void setOnStateAddCallback(const TrajectoryStateAddedCallback &callback)
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &package_name, const std::string &urdf_relative_path, const std::string &srdf_relative_path)
Loads a robot model given a URDF and SRDF file in a package.
std::function< void(sensor_msgs::msg::JointState::ConstSharedPtr)> JointStateUpdateCallback
MOCK_METHOD(std::string, getStaticTfTopicName,(),(const, override))
MOCK_METHOD(void, createDynamicTfSubscription,(TfCallback callback),(override))
MOCK_METHOD(std::string, getJointStateTopicName,(),(const, override))
MOCK_METHOD(void, resetTfSubscriptions,(),(override))
MOCK_METHOD(void, createJointStateSubscription,(const std::string &topic, planning_scene_monitor::JointStateUpdateCallback callback),(override))
MOCK_METHOD(bool, sleepFor,(const std::chrono::nanoseconds &nanoseconds),(const, override))
MOCK_METHOD(rclcpp::Time, now,(),(const, override))
MOCK_METHOD(void, resetJointStateSubscription,(),(override))
MOCK_METHOD(bool, ok,(),(const, override))
MOCK_METHOD(void, createStaticTfSubscription,(TfCallback callback),(override))
MOCK_METHOD(std::string, getDynamicTfTopicName,(),(const, override))
MOCK_METHOD(void, setRate,(double sampling_frequency),(override))
MOCK_METHOD(void, sleep,(),(override))
int main(int argc, char **argv)
TEST(TrajectoryMonitorTests, SleepAtLeastOnce)
void waitFor(std::chrono::seconds timeout, const std::function< bool()> &done)