|
| 1 | +// Copyright (c) 2022 Joshua Wallace |
| 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. Reserved. |
| 14 | + |
| 15 | +#include <gtest/gtest.h> |
| 16 | + |
| 17 | +#include <future> |
| 18 | + |
| 19 | +#include "nav2_costmap_2d/costmap_2d.hpp" |
| 20 | +#include "nav2_costmap_2d/costmap_subscriber.hpp" |
| 21 | +#include "nav2_costmap_2d/cost_values.hpp" |
| 22 | +#include "tf2_ros/transform_listener.h" |
| 23 | +#include "nav2_costmap_2d/costmap_2d_ros.hpp" |
| 24 | + |
| 25 | +class RclCppFixture |
| 26 | +{ |
| 27 | +public: |
| 28 | + RclCppFixture() {rclcpp::init(0, nullptr);} |
| 29 | + ~RclCppFixture() {rclcpp::shutdown();} |
| 30 | +}; |
| 31 | +RclCppFixture g_rclcppfixture; |
| 32 | + |
| 33 | +class CostmapRosLifecycleNode : public nav2_util::LifecycleNode |
| 34 | +{ |
| 35 | +public: |
| 36 | + explicit CostmapRosLifecycleNode(const std::string & name) |
| 37 | + : LifecycleNode(name), |
| 38 | + name_(name) {} |
| 39 | + |
| 40 | + ~CostmapRosLifecycleNode() override = default; |
| 41 | + |
| 42 | + nav2_util::CallbackReturn |
| 43 | + on_configure(const rclcpp_lifecycle::State &) override |
| 44 | + { |
| 45 | + costmap_ros_ = std::make_shared<nav2_costmap_2d::Costmap2DROS>( |
| 46 | + name_, |
| 47 | + std::string{get_namespace()}, |
| 48 | + name_, |
| 49 | + get_parameter("use_sim_time").as_bool()); |
| 50 | + costmap_thread_ = std::make_unique<nav2_util::NodeThread>(costmap_ros_); |
| 51 | + |
| 52 | + costmap_ros_->configure(); |
| 53 | + |
| 54 | + return nav2_util::CallbackReturn::SUCCESS; |
| 55 | + } |
| 56 | + |
| 57 | + nav2_util::CallbackReturn |
| 58 | + on_activate(const rclcpp_lifecycle::State &) override |
| 59 | + { |
| 60 | + costmap_ros_->activate(); |
| 61 | + return nav2_util::CallbackReturn::SUCCESS; |
| 62 | + } |
| 63 | + |
| 64 | + nav2_util::CallbackReturn |
| 65 | + on_deactivate(const rclcpp_lifecycle::State &) override |
| 66 | + { |
| 67 | + costmap_ros_->deactivate(); |
| 68 | + return nav2_util::CallbackReturn::SUCCESS; |
| 69 | + } |
| 70 | + |
| 71 | + nav2_util::CallbackReturn |
| 72 | + on_cleanup(const rclcpp_lifecycle::State &) override |
| 73 | + { |
| 74 | + costmap_thread_.reset(); |
| 75 | + costmap_ros_->deactivate(); |
| 76 | + return nav2_util::CallbackReturn::SUCCESS; |
| 77 | + } |
| 78 | + |
| 79 | +protected: |
| 80 | + std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_; |
| 81 | + std::unique_ptr<nav2_util::NodeThread> costmap_thread_; |
| 82 | + const std::string name_; |
| 83 | +}; |
| 84 | + |
| 85 | +class LayerSubscriber |
| 86 | +{ |
| 87 | +public: |
| 88 | + explicit LayerSubscriber(const nav2_util::LifecycleNode::WeakPtr & parent) |
| 89 | + { |
| 90 | + auto node = parent.lock(); |
| 91 | + |
| 92 | + callback_group_ = node->create_callback_group( |
| 93 | + rclcpp::CallbackGroupType::MutuallyExclusive, false); |
| 94 | + |
| 95 | + rclcpp::SubscriptionOptions sub_option; |
| 96 | + sub_option.callback_group = callback_group_; |
| 97 | + |
| 98 | + std::string topic_name = "/fake_costmap/static_layer_raw"; |
| 99 | + layer_sub_ = node->create_subscription<nav2_msgs::msg::Costmap>( |
| 100 | + topic_name, |
| 101 | + rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable(), |
| 102 | + std::bind(&LayerSubscriber::layerCallback, this, std::placeholders::_1), |
| 103 | + sub_option); |
| 104 | + |
| 105 | + executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>(); |
| 106 | + executor_->add_callback_group(callback_group_, node->get_node_base_interface()); |
| 107 | + executor_thread_ = std::make_unique<nav2_util::NodeThread>(executor_); |
| 108 | + } |
| 109 | + |
| 110 | + ~LayerSubscriber() |
| 111 | + { |
| 112 | + executor_thread_.reset(); |
| 113 | + } |
| 114 | + |
| 115 | + std::promise<nav2_msgs::msg::Costmap::SharedPtr> layer_promise_; |
| 116 | + |
| 117 | +protected: |
| 118 | + void layerCallback(const nav2_msgs::msg::Costmap::SharedPtr layer) |
| 119 | + { |
| 120 | + if (!callback_hit_) { |
| 121 | + layer_promise_.set_value(layer); |
| 122 | + callback_hit_ = true; |
| 123 | + } |
| 124 | + } |
| 125 | + |
| 126 | + rclcpp::Subscription<nav2_msgs::msg::Costmap>::SharedPtr layer_sub_; |
| 127 | + rclcpp::CallbackGroup::SharedPtr callback_group_; |
| 128 | + rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_; |
| 129 | + std::unique_ptr<nav2_util::NodeThread> executor_thread_; |
| 130 | + bool callback_hit_{false}; |
| 131 | +}; |
| 132 | + |
| 133 | +class CostmapRosTestFixture : public ::testing::Test |
| 134 | +{ |
| 135 | +public: |
| 136 | + CostmapRosTestFixture() |
| 137 | + { |
| 138 | + costmap_lifecycle_node_ = std::make_shared<CostmapRosLifecycleNode>("fake_costmap"); |
| 139 | + layer_subscriber_ = std::make_shared<LayerSubscriber>( |
| 140 | + costmap_lifecycle_node_->shared_from_this()); |
| 141 | + costmap_lifecycle_node_->on_configure(costmap_lifecycle_node_->get_current_state()); |
| 142 | + costmap_lifecycle_node_->on_activate(costmap_lifecycle_node_->get_current_state()); |
| 143 | + } |
| 144 | + |
| 145 | + ~CostmapRosTestFixture() override |
| 146 | + { |
| 147 | + costmap_lifecycle_node_->on_deactivate(costmap_lifecycle_node_->get_current_state()); |
| 148 | + costmap_lifecycle_node_->on_cleanup(costmap_lifecycle_node_->get_current_state()); |
| 149 | + } |
| 150 | + |
| 151 | +protected: |
| 152 | + std::shared_ptr<CostmapRosLifecycleNode> costmap_lifecycle_node_; |
| 153 | + std::shared_ptr<LayerSubscriber> layer_subscriber_; |
| 154 | +}; |
| 155 | + |
| 156 | +TEST_F(CostmapRosTestFixture, costmap_pub_test) |
| 157 | +{ |
| 158 | + auto future = layer_subscriber_->layer_promise_.get_future(); |
| 159 | + auto status = future.wait_for(std::chrono::seconds(5)); |
| 160 | + EXPECT_TRUE(status == std::future_status::ready); |
| 161 | + |
| 162 | + auto costmap_raw = future.get(); |
| 163 | + |
| 164 | + // Check first 20 cells of the 10by10 map |
| 165 | + unsigned int i = 0; |
| 166 | + for (; i < 7; ++i) { |
| 167 | + EXPECT_EQ(costmap_raw->data[i], nav2_costmap_2d::FREE_SPACE); |
| 168 | + } |
| 169 | + for (; i < 10; ++i) { |
| 170 | + EXPECT_EQ(costmap_raw->data[i++], nav2_costmap_2d::LETHAL_OBSTACLE); |
| 171 | + } |
| 172 | + for (; i < 17; ++i) { |
| 173 | + EXPECT_EQ(costmap_raw->data[i], nav2_costmap_2d::FREE_SPACE); |
| 174 | + } |
| 175 | + for (; i < 20; ++i) { |
| 176 | + EXPECT_EQ(costmap_raw->data[i++], nav2_costmap_2d::LETHAL_OBSTACLE); |
| 177 | + } |
| 178 | +} |
0 commit comments