Skip to content

Commit a4bf04b

Browse files
committed
DWB critics addition
Signed-off-by: silanus23 <berkantali23@outlook.com>
1 parent 4d28c13 commit a4bf04b

File tree

6 files changed

+308
-0
lines changed

6 files changed

+308
-0
lines changed

nav2_dwb_controller/dwb_critics/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,7 @@ add_library(${PROJECT_NAME} SHARED
3434
src/prefer_forward.cpp
3535
src/rotate_to_goal.cpp
3636
src/twirling.cpp
37+
src/path_hug.cpp
3738
)
3839
target_include_directories(${PROJECT_NAME} PUBLIC
3940
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"

nav2_dwb_controller/dwb_critics/default_critics.xml

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -38,5 +38,9 @@
3838
<description>Penalize trajectories with rotational velocities
3939
</description>
4040
</class>
41+
<class type="dwb_critics::PathHugCritic" base_class_type="dwb_core::TrajectoryCritic">
42+
<description>Penalize trajectories according to their distance to the path and their alignment with it.
43+
</description>
44+
</class>
4145
</library>
4246
</class_libraries>
Lines changed: 50 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,50 @@
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+
#ifndef DWB_CRITICS__PATH_HUG_HPP_
16+
#define DWB_CRITICS__PATH_HUG_HPP_
17+
18+
#include "dwb_critics/path_dist.hpp"
19+
20+
namespace dwb_critics
21+
{
22+
/**
23+
* @class PathHugCritic
24+
* @brief DWB critic that penalizes trajectories based on their distance from the global path.
25+
* Encourages the robot to "hug" or stay close to the path.
26+
*/
27+
class PathHugCritic : public PathDistCritic
28+
{
29+
public:
30+
void onInit() override;
31+
bool prepare(
32+
const geometry_msgs::msg::Pose & pose,
33+
const nav_2d_msgs::msg::Twist2D & vel,
34+
const geometry_msgs::msg::Pose & goal,
35+
const nav_msgs::msg::Path & global_plan) override;
36+
double getScale() const override;
37+
double scoreTrajectory(const dwb_msgs::msg::Trajectory2D & traj) override;
38+
39+
protected:
40+
bool zero_scale_{false};
41+
nav_msgs::msg::Path global_path_;
42+
size_t start_index_;
43+
geometry_msgs::msg::Pose current_pose_;
44+
double average_score_;
45+
double search_window_;
46+
};
47+
48+
} // namespace dwb_critics
49+
50+
#endif // DWB_CRITICS__PATH_HUG_HPP_
Lines changed: 84 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,84 @@
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 "dwb_critics/path_hug.hpp"
16+
#include <vector>
17+
#include <string>
18+
#include "dwb_critics/alignment_util.hpp"
19+
#include "pluginlib/class_list_macros.hpp"
20+
#include "nav2_util/path_utils.hpp"
21+
22+
namespace dwb_critics
23+
{
24+
25+
void PathHugCritic::onInit()
26+
{
27+
stop_on_failure_ = false;
28+
auto node = node_.lock();
29+
if (!node) {
30+
throw std::runtime_error{"Failed to lock node"};
31+
}
32+
33+
nav2::declare_parameter_if_not_declared(
34+
node, dwb_plugin_name_ + ".search_window", rclcpp::ParameterValue(2.0));
35+
node->get_parameter(dwb_plugin_name_ + ".search_window", search_window_);
36+
37+
if (search_window_ <= 0.0) {
38+
throw std::runtime_error{"search_window must be positive"};
39+
}
40+
}
41+
42+
bool PathHugCritic::prepare(
43+
const geometry_msgs::msg::Pose & /*pose*/, const nav_2d_msgs::msg::Twist2D & /*vel*/,
44+
const geometry_msgs::msg::Pose & /*goal*/,
45+
const nav_msgs::msg::Path & global_plan)
46+
{
47+
global_path_ = global_plan;
48+
return true;
49+
}
50+
51+
double PathHugCritic::scoreTrajectory(const dwb_msgs::msg::Trajectory2D & traj)
52+
{
53+
if (traj.poses.empty() || global_path_.poses.empty()) {
54+
return 0.0;
55+
}
56+
double distance = 0;
57+
58+
current_pose_ = traj.poses[0];
59+
nav2_util::PathSearchResult search_result = nav2_util::distance_from_path(
60+
global_path_, current_pose_);
61+
start_index_ = search_result.closest_segment_index;
62+
63+
for (size_t traj_index = 0; traj_index < traj.poses.size(); traj_index++) {
64+
search_result = nav2_util::distance_from_path(global_path_, traj.poses[traj_index],
65+
start_index_,
66+
search_window_);
67+
distance += search_result.distance;
68+
start_index_ = search_result.closest_segment_index;
69+
}
70+
return distance / traj.poses.size();
71+
}
72+
73+
double PathHugCritic::getScale() const
74+
{
75+
if (zero_scale_) {
76+
return 0.0;
77+
} else {
78+
return costmap_->getResolution() * 0.5;
79+
}
80+
}
81+
82+
} // namespace dwb_critics
83+
84+
PLUGINLIB_EXPORT_CLASS(dwb_critics::PathHugCritic, dwb_core::TrajectoryCritic)

nav2_dwb_controller/dwb_critics/test/CMakeLists.txt

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -33,3 +33,10 @@ target_link_libraries(twirling_tests
3333
dwb_core::dwb_core
3434
rclcpp::rclcpp
3535
)
36+
37+
ament_add_gtest(path_hug_tests path_hug_test.cpp)
38+
target_link_libraries(path_hug_tests
39+
dwb_critics
40+
dwb_core::dwb_core
41+
rclcpp::rclcpp
42+
)
Lines changed: 162 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,162 @@
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

Comments
 (0)