|
| 1 | +// Copyright (c) 2025, Berkan Tali |
| 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 <memory> |
| 17 | +#include "dwb_critics/path_hug.hpp" |
| 18 | +#include "nav2_costmap_2d/costmap_2d_ros.hpp" |
| 19 | +#include "nav2_ros_common/lifecycle_node.hpp" |
| 20 | +#include "nav_2d_msgs/msg/twist2_d.hpp" |
| 21 | +#include "nav_msgs/msg/path.hpp" |
| 22 | +#include "dwb_msgs/msg/trajectory2_d.hpp" |
| 23 | + |
| 24 | +static constexpr double default_forward_point_distance = 0.325; |
| 25 | + |
| 26 | +class PathHugCriticTest : public ::testing::Test |
| 27 | +{ |
| 28 | +protected: |
| 29 | + void SetUp() override |
| 30 | + { |
| 31 | + node_ = std::make_shared<nav2::LifecycleNode>("test_node"); |
| 32 | + node_->configure(); |
| 33 | + node_->activate(); |
| 34 | + |
| 35 | + costmap_ros_ = std::make_shared<nav2_costmap_2d::Costmap2DROS>("test_global_costmap", "", |
| 36 | + false); |
| 37 | + costmap_ros_->configure(); |
| 38 | + |
| 39 | + std::string name = "PathHugCritic"; |
| 40 | + critic_ = std::make_shared<dwb_critics::PathHugCritic>(); |
| 41 | + critic_->initialize(node_, name, "", costmap_ros_); |
| 42 | + critic_->onInit(); |
| 43 | + } |
| 44 | + |
| 45 | + geometry_msgs::msg::Pose makePose(double x, double y) |
| 46 | + { |
| 47 | + geometry_msgs::msg::Pose pose; |
| 48 | + pose.position.x = x; |
| 49 | + pose.position.y = y; |
| 50 | + pose.orientation.w = 1.0; |
| 51 | + return pose; |
| 52 | + } |
| 53 | + |
| 54 | + nav_msgs::msg::Path makePath(std::vector<std::pair<double, double>> points) |
| 55 | + { |
| 56 | + nav_msgs::msg::Path path; |
| 57 | + for (const auto & pt : points) { |
| 58 | + geometry_msgs::msg::PoseStamped ps; |
| 59 | + ps.pose = makePose(pt.first, pt.second); |
| 60 | + path.poses.push_back(ps); |
| 61 | + } |
| 62 | + return path; |
| 63 | + } |
| 64 | + |
| 65 | + dwb_msgs::msg::Trajectory2D makeTrajectory(std::vector<std::pair<double, double>> points) |
| 66 | + { |
| 67 | + dwb_msgs::msg::Trajectory2D traj; |
| 68 | + for (const auto & pt : points) { |
| 69 | + geometry_msgs::msg::Pose pose; |
| 70 | + pose.position.x = pt.first; |
| 71 | + pose.position.y = pt.second; |
| 72 | + pose.orientation.w = 0.0; |
| 73 | + traj.poses.push_back(pose); |
| 74 | + } |
| 75 | + return traj; |
| 76 | + } |
| 77 | + |
| 78 | + std::shared_ptr<nav2::LifecycleNode> node_; |
| 79 | + std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_; |
| 80 | + std::shared_ptr<dwb_critics::PathHugCritic> critic_; |
| 81 | +}; |
| 82 | + |
| 83 | +TEST_F(PathHugCriticTest, DefaultParameterInitialization) |
| 84 | +{ |
| 85 | + node_->declare_parameter("PathHugCritic.forward_point_distance", default_forward_point_distance); |
| 86 | + EXPECT_EQ( |
| 87 | + node_->get_parameter("PathHugCritic.forward_point_distance").as_double(), |
| 88 | + default_forward_point_distance); |
| 89 | +} |
| 90 | + |
| 91 | +TEST_F(PathHugCriticTest, HandlesEmptyTrajectory) |
| 92 | +{ |
| 93 | + nav_msgs::msg::Path path = makePath({{0.0, 0.0}, {1.0, 1.0}}); |
| 94 | + critic_->prepare(makePose(0, 0), nav_2d_msgs::msg::Twist2D(), makePose(1, 1), path); |
| 95 | + |
| 96 | + dwb_msgs::msg::Trajectory2D traj; |
| 97 | + EXPECT_DOUBLE_EQ(critic_->scoreTrajectory(traj), 0.0); |
| 98 | +} |
| 99 | + |
| 100 | +TEST_F(PathHugCriticTest, HandlesEmptyGlobalPath) |
| 101 | +{ |
| 102 | + nav_msgs::msg::Path path; |
| 103 | + critic_->prepare(makePose(0, 0), nav_2d_msgs::msg::Twist2D(), makePose(1, 1), path); |
| 104 | + |
| 105 | + dwb_msgs::msg::Trajectory2D traj = makeTrajectory({{0.0, 0.0}, {1.0, 1.0}}); |
| 106 | + EXPECT_DOUBLE_EQ(critic_->scoreTrajectory(traj), 0.0); |
| 107 | +} |
| 108 | + |
| 109 | +TEST_F(PathHugCriticTest, ScoresTrajectoryNearPath) |
| 110 | +{ |
| 111 | + nav_msgs::msg::Path path = makePath({{0.0, 0.0}, {1.0, 1.0}}); |
| 112 | + critic_->prepare(makePose(0, 0), nav_2d_msgs::msg::Twist2D(), makePose(1, 1), path); |
| 113 | + |
| 114 | + dwb_msgs::msg::Trajectory2D traj = makeTrajectory({{0.0, 0.0}, {0.5, 0.5}, {1.0, 1.0}}); |
| 115 | + double score = critic_->scoreTrajectory(traj); |
| 116 | + EXPECT_GE(score, 0.0); |
| 117 | +} |
| 118 | + |
| 119 | +TEST_F(PathHugCriticTest, ScoresTrajectoryFarFromPath) |
| 120 | +{ |
| 121 | + nav_msgs::msg::Path path = makePath({{0.0, 0.0}, {1.0, 1.0}}); |
| 122 | + critic_->prepare(makePose(0, 0), nav_2d_msgs::msg::Twist2D(), makePose(1, 1), path); |
| 123 | + |
| 124 | + dwb_msgs::msg::Trajectory2D traj = makeTrajectory({{5.0, 5.0}, {6.0, 6.0}}); |
| 125 | + double score = critic_->scoreTrajectory(traj); |
| 126 | + EXPECT_GT(score, 0.0); |
| 127 | +} |
| 128 | + |
| 129 | +TEST_F(PathHugCriticTest, CustomParameterValues) |
| 130 | +{ |
| 131 | + auto custom_node = std::make_shared<nav2::LifecycleNode>("custom_test_node"); |
| 132 | + custom_node->configure(); |
| 133 | + custom_node->activate(); |
| 134 | + |
| 135 | + double custom_distance = 1.0; |
| 136 | + std::string name = "PathHugCritic"; |
| 137 | + |
| 138 | + nav2::declare_parameter_if_not_declared( |
| 139 | + custom_node, name + ".forward_point_distance", |
| 140 | + rclcpp::ParameterValue(custom_distance)); |
| 141 | + |
| 142 | + auto custom_critic = std::make_shared<dwb_critics::PathHugCritic>(); |
| 143 | + auto custom_costmap = std::make_shared<nav2_costmap_2d::Costmap2DROS>("custom_costmap", "", |
| 144 | + false); |
| 145 | + custom_costmap->configure(); |
| 146 | + |
| 147 | + custom_critic->initialize(custom_node, name, "", custom_costmap); |
| 148 | + custom_critic->onInit(); |
| 149 | + |
| 150 | + EXPECT_EQ( |
| 151 | + custom_node->get_parameter(name + ".forward_point_distance").as_double(), |
| 152 | + custom_distance); |
| 153 | +} |
| 154 | + |
| 155 | +int main(int argc, char ** argv) |
| 156 | +{ |
| 157 | + ::testing::InitGoogleTest(&argc, argv); |
| 158 | + rclcpp::init(argc, argv); |
| 159 | + int result = RUN_ALL_TESTS(); |
| 160 | + rclcpp::shutdown(); |
| 161 | + return result; |
| 162 | +} |
0 commit comments