41 #include <gmock/gmock.h>
42 #include <gtest/gtest.h>
46 #include <rclcpp/rclcpp.hpp>
47 #include <tf2_ros/buffer.h>
49 using namespace std::chrono_literals;
53 MOCK_METHOD(
void, setRate, (
double sampling_frequency), (
override));
62 MOCK_METHOD(
void, resetJointStateSubscription, (), (
override));
63 MOCK_METHOD(std::string, getJointStateTopicName, (), (
const,
override));
64 MOCK_METHOD(
bool, sleepFor, (
const std::chrono::nanoseconds& nanoseconds), (
const,
override));
68 MOCK_METHOD(std::string, getStaticTfTopicName, (), (
const,
override));
69 MOCK_METHOD(std::string, getDynamicTfTopicName, (), (
const,
override));
73 void 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);
86 TEST(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); });
113 int main(
int argc,
char** argv)
115 ::testing::InitGoogleTest(&argc, argv);
116 return RUN_ALL_TESTS();
Dependency injection class for testing the CurrentStateMonitor.
std::function< void(const tf2_msgs::msg::TFMessage::ConstSharedPtr)> TfCallback
This class contains the rcl interfaces for easier testing.
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 &robot_name)
Loads a robot from moveit_resources.
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)