moveit2
The MoveIt Motion Planning Framework for ROS 2.
trajectory_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: Abishalini Sivaraman */
36 
37 #include <memory>
38 #include <chrono>
39 #include <thread>
40 #include <atomic>
41 #include <gmock/gmock.h>
42 #include <gtest/gtest.h>
46 #include <rclcpp/rclcpp.hpp>
47 #include <tf2_ros/buffer.h>
48 
49 using namespace std::chrono_literals;
50 
52 {
53  MOCK_METHOD(void, setRate, (double sampling_frequency), (override));
54  MOCK_METHOD(void, sleep, (), (override));
55 };
56 
58 {
59  MOCK_METHOD(rclcpp::Time, now, (), (const, override));
60  MOCK_METHOD(void, createJointStateSubscription,
61  (const std::string& topic, planning_scene_monitor::JointStateUpdateCallback callback), (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));
65  MOCK_METHOD(bool, ok, (), (const, override));
66  MOCK_METHOD(void, createStaticTfSubscription, (TfCallback callback), (override));
67  MOCK_METHOD(void, createDynamicTfSubscription, (TfCallback callback), (override));
68  MOCK_METHOD(std::string, getStaticTfTopicName, (), (const, override));
69  MOCK_METHOD(std::string, getDynamicTfTopicName, (), (const, override));
70  MOCK_METHOD(void, resetTfSubscriptions, (), (override));
71 };
72 
73 void waitFor(std::chrono::seconds timeout, const std::function<bool()>& done)
74 {
75  const auto start = std::chrono::steady_clock::now();
76  while ((std::chrono::steady_clock::now() - start) < timeout)
77  {
78  if (done())
79  {
80  return;
81  }
82  std::this_thread::sleep_for(1ms);
83  }
84 }
85 
86 TEST(TrajectoryMonitorTests, SleepAtLeastOnce)
87 {
88  auto mock_trajectory_monitor_middleware_handle = std::make_unique<MockTrajectoryMonitorMiddlewareHandle>();
89  auto mock_current_state_monitor_middleware_handle = std::make_unique<MockCurrentStateMonitorMiddlewareHandle>();
90 
91  // THEN we expect it to call sleep function
92  EXPECT_CALL(*mock_trajectory_monitor_middleware_handle, sleep).Times(::testing::AtLeast(1));
93 
94  // GIVEN a TrajectoryMonitor is started
95  auto current_state_monitor = std::make_shared<planning_scene_monitor::CurrentStateMonitor>(
96  std::move(mock_current_state_monitor_middleware_handle), moveit::core::loadTestingRobotModel("panda"),
97  std::make_shared<tf2_ros::Buffer>(std::make_shared<rclcpp::Clock>()), false);
98 
99  planning_scene_monitor::TrajectoryMonitor trajectory_monitor{ current_state_monitor,
100  std::move(mock_trajectory_monitor_middleware_handle),
101  10.0 };
102 
103  // Set the trajectory monitor callback so we can block until at least one sample was taken.
104  std::atomic<bool> callback_called{ false };
105  trajectory_monitor.setOnStateAddCallback([&](const moveit::core::RobotStateConstPtr& /* unused */,
106  const rclcpp::Time& /* unused */) { callback_called = true; });
107 
108  // WHEN we call the startTrajectoryMonitor function
109  trajectory_monitor.startTrajectoryMonitor();
110  waitFor(10s, [&]() { return static_cast<bool>(callback_called); });
111 }
112 
113 int main(int argc, char** argv)
114 {
115  ::testing::InitGoogleTest(&argc, argv);
116  return RUN_ALL_TESTS();
117 }
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)