41 #include <gmock/gmock.h>
42 #include <gtest/gtest.h>
45 #include <rclcpp/rclcpp.hpp>
46 #include <tf2_ros/buffer.h>
64 TEST(CurrentStateMonitorTests, StartCreateSubscriptionTest)
66 auto mock_middleware_handle = std::make_unique<MockMiddlewareHandle>();
68 EXPECT_CALL(*mock_middleware_handle, createJointStateSubscription);
73 std::make_shared<tf2_ros::Buffer>(std::make_shared<rclcpp::Clock>()),
false
77 current_state_monitor.startStateMonitor();
80 TEST(CurrentStateMonitorTests, StartActiveTest)
85 std::make_shared<tf2_ros::Buffer>(std::make_shared<rclcpp::Clock>()),
false
89 current_state_monitor.startStateMonitor();
92 EXPECT_TRUE(current_state_monitor.isActive());
95 TEST(CurrentStateMonitorTests, StopResetSubscriptionTest)
97 auto mock_middleware_handle = std::make_unique<MockMiddlewareHandle>();
100 EXPECT_CALL(*mock_middleware_handle, resetJointStateSubscription);
101 EXPECT_CALL(*mock_middleware_handle, now);
106 std::make_shared<tf2_ros::Buffer>(std::make_shared<rclcpp::Clock>()),
false
108 current_state_monitor.startStateMonitor();
111 current_state_monitor.stopStateMonitor();
114 TEST(CurrentStateMonitorTests, StopNotActiveTest)
116 auto mock_middleware_handle = std::make_unique<MockMiddlewareHandle>();
121 std::make_shared<tf2_ros::Buffer>(std::make_shared<rclcpp::Clock>()),
false
123 current_state_monitor.startStateMonitor();
126 current_state_monitor.stopStateMonitor();
129 EXPECT_FALSE(current_state_monitor.isActive());
132 TEST(CurrentStateMonitorTests, DestructStopTest)
134 auto mock_middleware_handle = std::make_unique<MockMiddlewareHandle>();
137 EXPECT_CALL(*mock_middleware_handle, resetJointStateSubscription);
138 EXPECT_CALL(*mock_middleware_handle, now);
144 std::make_shared<tf2_ros::Buffer>(std::make_shared<rclcpp::Clock>()),
false
146 current_state_monitor.startStateMonitor();
147 EXPECT_TRUE(current_state_monitor.isActive());
152 TEST(CurrentStateMonitorTests, NoModelTest)
155 moveit::core::RobotModelPtr robot_model =
nullptr;
160 std::make_unique<MockMiddlewareHandle>(), robot_model,
161 std::make_shared<tf2_ros::Buffer>(std::make_shared<rclcpp::Clock>()),
false),
162 std::invalid_argument);
165 TEST(CurrentStateMonitorTests, HaveCompleteStateConstructFalse)
170 std::make_shared<tf2_ros::Buffer>(std::make_shared<rclcpp::Clock>()),
false
175 EXPECT_FALSE(current_state_monitor.haveCompleteState());
178 TEST(CurrentStateMonitorTests, WaitForCompleteStateWaits)
180 auto mock_middleware_handle = std::make_unique<MockMiddlewareHandle>();
182 auto nanoseconds_slept = std::chrono::nanoseconds(0);
183 ON_CALL(*mock_middleware_handle, sleepFor)
184 .WillByDefault(testing::Invoke([&](
const std::chrono::nanoseconds& nanoseconds) {
185 nanoseconds_slept += nanoseconds;
192 std::make_shared<tf2_ros::Buffer>(std::make_shared<rclcpp::Clock>()),
false
196 current_state_monitor.waitForCompleteState(1.0);
199 EXPECT_NEAR(nanoseconds_slept.count(), 1e+9, 1e3);
202 int main(
int argc,
char** argv)
204 ::testing::InitGoogleTest(&argc, argv);
205 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.
Monitors the joint_states topic and tf to maintain the current state of the robot.
int main(int argc, char **argv)
TEST(CurrentStateMonitorTests, StartCreateSubscriptionTest)
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(void, resetTfSubscriptions,(),(override))
MOCK_METHOD(std::string, getDynamicTfTopicName,(),(const, override))
MOCK_METHOD(bool, ok,(),(const, override))
MOCK_METHOD(void, resetJointStateSubscription,(),(override))
MOCK_METHOD(rclcpp::Time, now,(),(const, 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(void, createStaticTfSubscription,(TfCallback callback),(override))
MOCK_METHOD(std::string, getJointStateTopicName,(),(const, override))
MOCK_METHOD(void, createDynamicTfSubscription,(TfCallback callback),(override))
MOCK_METHOD(std::string, getStaticTfTopicName,(),(const, override))