39#include <gmock/gmock.h>
40#include <gtest/gtest.h>
41#include <rclcpp/version.h>
43#if RCLCPP_VERSION_GTE(29, 6, 0)
44#include <tf2_ros/buffer.hpp>
47#include <tf2_ros/buffer.h>
59 (
const std::string& sensor_plugin), (
override));
61 (occupancy_map_monitor::OccupancyMapUpdaterPtr occupancy_map_updater), (
override));
70TEST(OccupancyMapMonitorTests, ConstructorTest)
73 auto mock_middleware_handle = std::make_unique<MockMiddlewareHandle>();
76 EXPECT_CALL(*mock_middleware_handle, getParameters).Times(1);
77 EXPECT_CALL(*mock_middleware_handle, createSaveMapService).Times(1);
78 EXPECT_CALL(*mock_middleware_handle, createLoadMapService).Times(1);
79 EXPECT_CALL(*mock_middleware_handle, loadOccupancyMapUpdater).Times(0);
83 std::move(mock_middleware_handle), std::make_shared<tf2_ros::Buffer>(std::make_shared<rclcpp::Clock>())
87int main(
int argc,
char** argv)
89 ::testing::InitGoogleTest(&argc, argv);
90 return RUN_ALL_TESTS();
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.