moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
current_state_monitor_tests.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2021, PickNik, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of PickNik nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Tyler Weaver */
36
37#include <chrono>
38#include <memory>
39#include <string>
40
41#include <gmock/gmock.h>
42#include <gtest/gtest.h>
45#include <rclcpp/rclcpp.hpp>
46#include <tf2_ros/buffer.h>
47
49{
50 MOCK_METHOD(rclcpp::Time, now, (), (const, override));
52 (const std::string& topic, planning_scene_monitor::JointStateUpdateCallback callback), (override));
54 MOCK_METHOD(std::string, getJointStateTopicName, (), (const, override));
55 MOCK_METHOD(bool, sleepFor, (const std::chrono::nanoseconds& nanoseconds), (const, override));
56 MOCK_METHOD(bool, ok, (), (const, override));
57 MOCK_METHOD(void, createStaticTfSubscription, (TfCallback callback), (override));
58 MOCK_METHOD(void, createDynamicTfSubscription, (TfCallback callback), (override));
59 MOCK_METHOD(std::string, getStaticTfTopicName, (), (const, override));
60 MOCK_METHOD(std::string, getDynamicTfTopicName, (), (const, override));
61 MOCK_METHOD(void, resetTfSubscriptions, (), (override));
62};
63
64TEST(CurrentStateMonitorTests, StartCreateSubscriptionTest)
65{
66 auto mock_middleware_handle = std::make_unique<MockMiddlewareHandle>();
67 // THEN we expect it to call createJointStateSubscription on the MiddlewareHandle
68 EXPECT_CALL(*mock_middleware_handle, createJointStateSubscription);
69
70 // GIVEN a CurrentStateMonitor
72 std::move(mock_middleware_handle), moveit::core::loadTestingRobotModel("panda"),
73 std::make_shared<tf2_ros::Buffer>(std::make_shared<rclcpp::Clock>()), false
74 };
75
76 // WHEN we start the current state monitor
77 current_state_monitor.startStateMonitor();
78}
79
80TEST(CurrentStateMonitorTests, StartActiveTest)
81{
82 // GIVEN a CurrentStateMonitor
84 std::make_unique<MockMiddlewareHandle>(), moveit::core::loadTestingRobotModel("panda"),
85 std::make_shared<tf2_ros::Buffer>(std::make_shared<rclcpp::Clock>()), false
86 };
87
88 // WHEN we start the current state monitor
89 current_state_monitor.startStateMonitor();
90
91 // THEN we expect it to be active
92 EXPECT_TRUE(current_state_monitor.isActive());
93}
94
95TEST(CurrentStateMonitorTests, StopResetSubscriptionTest)
96{
97 auto mock_middleware_handle = std::make_unique<MockMiddlewareHandle>();
98
99 // THEN we expect it to call now and resetJointStateSubscription on the MiddlewareHandle
100 EXPECT_CALL(*mock_middleware_handle, resetJointStateSubscription);
101 EXPECT_CALL(*mock_middleware_handle, now);
102
103 // GIVEN a CurrentStateMonitor that is started
105 std::move(mock_middleware_handle), moveit::core::loadTestingRobotModel("panda"),
106 std::make_shared<tf2_ros::Buffer>(std::make_shared<rclcpp::Clock>()), false
107 };
108 current_state_monitor.startStateMonitor();
109
110 // WHEN we stop the current state monitor
111 current_state_monitor.stopStateMonitor();
112}
113
114TEST(CurrentStateMonitorTests, StopNotActiveTest)
115{
116 auto mock_middleware_handle = std::make_unique<MockMiddlewareHandle>();
117
118 // GIVEN a CurrentStateMonitor that is started
120 std::move(mock_middleware_handle), moveit::core::loadTestingRobotModel("panda"),
121 std::make_shared<tf2_ros::Buffer>(std::make_shared<rclcpp::Clock>()), false
122 };
123 current_state_monitor.startStateMonitor();
124
125 // WHEN we stop the current state monitor
126 current_state_monitor.stopStateMonitor();
127
128 // THEN we expect it to not be active
129 EXPECT_FALSE(current_state_monitor.isActive());
130}
131
132TEST(CurrentStateMonitorTests, DestructStopTest)
133{
134 auto mock_middleware_handle = std::make_unique<MockMiddlewareHandle>();
135
136 // THEN we expect it to be stopped and resetJointStateSubscription and now to be called
137 EXPECT_CALL(*mock_middleware_handle, resetJointStateSubscription);
138 EXPECT_CALL(*mock_middleware_handle, now);
139
140 // GIVEN a CurrentStateMonitor that we started
141 {
143 std::move(mock_middleware_handle), moveit::core::loadTestingRobotModel("panda"),
144 std::make_shared<tf2_ros::Buffer>(std::make_shared<rclcpp::Clock>()), false
145 };
146 current_state_monitor.startStateMonitor();
147 EXPECT_TRUE(current_state_monitor.isActive());
148 }
149 // WHEN it is destructed
150}
151
152TEST(CurrentStateMonitorTests, NoModelTest)
153{
154 // GIVEN an uninitialized robot model
155 moveit::core::RobotModelPtr robot_model = nullptr;
156
157 // WHEN the CurrentStateMonitor is constructed with it
158 // THEN we expect the monitor to throw because of the invalid model
160 std::make_unique<MockMiddlewareHandle>(), robot_model,
161 std::make_shared<tf2_ros::Buffer>(std::make_shared<rclcpp::Clock>()), false),
162 std::invalid_argument);
163}
164
165TEST(CurrentStateMonitorTests, HaveCompleteStateConstructFalse)
166{
167 // GIVEN a CurrentStateMonitor
169 std::make_unique<MockMiddlewareHandle>(), moveit::core::loadTestingRobotModel("panda"),
170 std::make_shared<tf2_ros::Buffer>(std::make_shared<rclcpp::Clock>()), false
171 };
172
173 // WHEN it is constructed
174 // THEN we expect haveCompleteState to be false
175 EXPECT_FALSE(current_state_monitor.haveCompleteState());
176}
177
178TEST(CurrentStateMonitorTests, WaitForCompleteStateWaits)
179{
180 auto mock_middleware_handle = std::make_unique<MockMiddlewareHandle>();
181
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;
186 return true;
187 }));
188
189 // GIVEN a CurrentStateMonitor
191 std::move(mock_middleware_handle), moveit::core::loadTestingRobotModel("panda"),
192 std::make_shared<tf2_ros::Buffer>(std::make_shared<rclcpp::Clock>()), false
193 };
194
195 // WHEN we wait for complete state for 1s
196 current_state_monitor.waitForCompleteState(1.0);
197
198 // THEN we expect it waited for near 1 seconds
199 EXPECT_NEAR(nanoseconds_slept.count(), 1e+9, 1e3);
200}
201
202int main(int argc, char** argv)
203{
204 ::testing::InitGoogleTest(&argc, argv);
205 return RUN_ALL_TESTS();
206}
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.
void startStateMonitor(const std::string &joint_states_topic="joint_states")
Start monitoring joint states on a particular topic.
bool waitForCompleteState(double wait_time_s) const
Wait for at most wait_time_s seconds until the complete robot state is known.
int main(int argc, char **argv)
TEST(CurrentStateMonitorTests, StartCreateSubscriptionTest)
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(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))