moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
occupancy_map_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
38
39#include <gmock/gmock.h>
40#include <gtest/gtest.h>
41#include <tf2_ros/buffer.h>
42
43#include <memory>
44#include <string>
45#include <utility>
46#include <vector>
47
49{
51 MOCK_METHOD(occupancy_map_monitor::OccupancyMapUpdaterPtr, loadOccupancyMapUpdater,
52 (const std::string& sensor_plugin), (override));
54 (occupancy_map_monitor::OccupancyMapUpdaterPtr occupancy_map_updater), (override));
57 (override));
60 (override));
61};
62
63TEST(OccupancyMapMonitorTests, ConstructorTest)
64{
65 // GIVEN a mocked middleware handle
66 auto mock_middleware_handle = std::make_unique<MockMiddlewareHandle>();
67
68 // THEN we expect it to call these methods on the MiddlewareHandle
69 EXPECT_CALL(*mock_middleware_handle, getParameters).Times(1);
70 EXPECT_CALL(*mock_middleware_handle, createSaveMapService).Times(1);
71 EXPECT_CALL(*mock_middleware_handle, createLoadMapService).Times(1);
72 EXPECT_CALL(*mock_middleware_handle, loadOccupancyMapUpdater).Times(0);
73
74 // WHEN we construct the occupancy map monitor
76 std::move(mock_middleware_handle), std::make_shared<tf2_ros::Buffer>(std::make_shared<rclcpp::Clock>())
77 };
78}
79
80int main(int argc, char** argv)
81{
82 ::testing::InitGoogleTest(&argc, argv);
83 return RUN_ALL_TESTS();
84}
This class contains the rcl interfaces for easier testing.
virtual OccupancyMapUpdaterPtr loadOccupancyMapUpdater(const std::string &sensor_plugin)=0
Loads an occupancy map updater based on string.
virtual void createLoadMapService(LoadMapServiceCallback callback)=0
Creates a load map service.
std::function< bool(const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< moveit_msgs::srv::LoadMap::Request > request, std::shared_ptr< moveit_msgs::srv::LoadMap::Response > response)> LoadMapServiceCallback
virtual Parameters getParameters() const =0
Gets the parameters struct.
std::function< bool(const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< moveit_msgs::srv::SaveMap::Request > request, std::shared_ptr< moveit_msgs::srv::SaveMap::Response > response)> SaveMapServiceCallback
virtual void createSaveMapService(SaveMapServiceCallback callback)=0
Creates a save map service.
virtual void initializeOccupancyMapUpdater(OccupancyMapUpdaterPtr occupancy_map_updater)=0
Initializes the occupancy map updater. Needed because of interface to OccupancyMapUpdater.
int main(int argc, char **argv)
TEST(OccupancyMapMonitorTests, ConstructorTest)
MOCK_METHOD(occupancy_map_monitor::OccupancyMapUpdaterPtr, loadOccupancyMapUpdater,(const std::string &sensor_plugin),(override))
MOCK_METHOD(occupancy_map_monitor::OccupancyMapMonitor::Parameters, getParameters,(),(const, override))
MOCK_METHOD(void, createLoadMapService,(occupancy_map_monitor::OccupancyMapMonitor::MiddlewareHandle::LoadMapServiceCallback callback),(override))
MOCK_METHOD(void, createSaveMapService,(occupancy_map_monitor::OccupancyMapMonitor::MiddlewareHandle::SaveMapServiceCallback callback),(override))
MOCK_METHOD(void, initializeOccupancyMapUpdater,(occupancy_map_monitor::OccupancyMapUpdaterPtr occupancy_map_updater),(override))
This class describes parameters that are normally provided through ROS Parameters.