|
| 1 | +// Copyright (c) 2020 Samsung Research America |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | + |
| 15 | +#include <gtest/gtest.h> |
| 16 | +#include <experimental/filesystem> |
| 17 | +#include <string> |
| 18 | +#include <memory> |
| 19 | +#include <utility> |
| 20 | + |
| 21 | +#include "rclcpp/rclcpp.hpp" |
| 22 | +#include "nav_msgs/msg/occupancy_grid.hpp" |
| 23 | + |
| 24 | +TEST(MapSaverCLI, CLITest) |
| 25 | +{ |
| 26 | + std::string path = "/tmp/"; |
| 27 | + std::string file = "test_map"; |
| 28 | + std::string file_path = path + file; |
| 29 | + |
| 30 | + rclcpp::init(0, nullptr); |
| 31 | + |
| 32 | + auto node = std::make_shared<rclcpp::Node>("CLI_Test_Node"); |
| 33 | + RCLCPP_INFO(node->get_logger(), "Testing Map Saver CLI"); |
| 34 | + |
| 35 | + auto publisher = node->create_publisher<nav_msgs::msg::OccupancyGrid>( |
| 36 | + "/map", |
| 37 | + rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable()); |
| 38 | + |
| 39 | + auto msg = std::make_unique<nav_msgs::msg::OccupancyGrid>(); |
| 40 | + msg->header.frame_id = "map"; |
| 41 | + msg->header.stamp = node->now(); |
| 42 | + msg->info.map_load_time = node->now(); |
| 43 | + msg->info.resolution = 0.05; |
| 44 | + msg->info.width = 3; |
| 45 | + msg->info.height = 3; |
| 46 | + msg->info.origin.position.x = 0.0; |
| 47 | + msg->info.origin.position.y = 0.0; |
| 48 | + msg->info.origin.orientation.w = 1.0; |
| 49 | + msg->data.resize(9); |
| 50 | + |
| 51 | + RCLCPP_INFO(node->get_logger(), "Publishing occupancy grid..."); |
| 52 | + |
| 53 | + publisher->publish(std::move(msg)); |
| 54 | + |
| 55 | + rclcpp::Rate(1).sleep(); |
| 56 | + |
| 57 | + // succeed on real map |
| 58 | + RCLCPP_INFO(node->get_logger(), "Calling saver..."); |
| 59 | + |
| 60 | + EXPECT_FALSE(std::experimental::filesystem::exists(file_path + ".yaml")); |
| 61 | + |
| 62 | + std::string command = |
| 63 | + std::string( |
| 64 | + "ros2 run nav2_map_server map_saver_cli -f ") + file_path; |
| 65 | + auto return_code = system(command.c_str()); |
| 66 | + EXPECT_EQ(return_code, 0); |
| 67 | + |
| 68 | + rclcpp::Rate(0.25).sleep(); |
| 69 | + |
| 70 | + RCLCPP_INFO(node->get_logger(), "Checking on file..."); |
| 71 | + |
| 72 | + EXPECT_TRUE(std::experimental::filesystem::exists(file_path + ".pgm")); |
| 73 | + EXPECT_EQ(std::experimental::filesystem::file_size(file_path + ".pgm"), 20ul); |
| 74 | + |
| 75 | + if (std::experimental::filesystem::exists(file_path + ".yaml")) { |
| 76 | + std::experimental::filesystem::remove(file_path + ".yaml"); |
| 77 | + } |
| 78 | + if (std::experimental::filesystem::exists(file_path + ".pgm")) { |
| 79 | + std::experimental::filesystem::remove(file_path + ".pgm"); |
| 80 | + } |
| 81 | + |
| 82 | + // fail on bogus map |
| 83 | + RCLCPP_INFO(node->get_logger(), "Calling saver..."); |
| 84 | + |
| 85 | + EXPECT_FALSE(std::experimental::filesystem::exists(file_path + ".yaml")); |
| 86 | + |
| 87 | + command = |
| 88 | + std::string( |
| 89 | + "ros2 run nav2_map_server map_saver_cli " |
| 90 | + "-t map_failure --occ 100 --free 2 --mode trinary --fmt png -f ") + file_path; |
| 91 | + return_code = system(command.c_str()); |
| 92 | + EXPECT_EQ(return_code, 256); |
| 93 | + |
| 94 | + rclcpp::Rate(0.25).sleep(); |
| 95 | + |
| 96 | + RCLCPP_INFO(node->get_logger(), "Checking on file..."); |
| 97 | + |
| 98 | + EXPECT_FALSE(std::experimental::filesystem::exists(file_path + ".yaml")); |
| 99 | +} |
0 commit comments