Skip to content

Commit 0b92a11

Browse files
authored
[All 2D planners] Fix last pose orientation, fix small path and add ignore_goal_orientation parameter (#2488)
* end point orientation * add ignore_goal_orientation to dyn param * back() instead of [path.poses.size() - 1] * Smac2d use_final_approach_orientation name * add in NavFn * add in theta_star * wip * deal with navfn double end pose case * add tests * back and revert test smac2d * get path hotfix * navfn wip * Corner cases * Checks consistency accross the 3 2D planners * comment * interpolate final orientation in planner instead of smoother * clarify and homogenize comments * using same cell test instead of distance compared to resolution * remove unneeded else * lint * fix smac2d goal orientation override * fix and add tests * update comment * typo * simplify if (_use_final_approach_orientation) block
1 parent 28b3418 commit 0b92a11

File tree

8 files changed

+301
-9
lines changed

8 files changed

+301
-9
lines changed

nav2_navfn_planner/include/nav2_navfn_planner/navfn_planner.hpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,7 @@
3030
#include "nav2_util/robot_utils.hpp"
3131
#include "nav2_util/lifecycle_node.hpp"
3232
#include "nav2_costmap_2d/costmap_2d_ros.hpp"
33+
#include "nav2_util/geometry_utils.hpp"
3334

3435
namespace nav2_navfn_planner
3536
{
@@ -205,7 +206,7 @@ class NavfnPlanner : public nav2_core::GlobalPlanner
205206
std::string global_frame_, name_;
206207

207208
// Whether or not the planner should be allowed to plan through unknown space
208-
bool allow_unknown_;
209+
bool allow_unknown_, use_final_approach_orientation_;
209210

210211
// If the goal is obstructed, the tolerance specifies how many meters the planner
211212
// can relax the constraint in x and y before failing

nav2_navfn_planner/src/navfn_planner.cpp

Lines changed: 59 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -85,6 +85,9 @@ NavfnPlanner::configure(
8585
node->get_parameter(name + ".use_astar", use_astar_);
8686
declare_parameter_if_not_declared(node, name + ".allow_unknown", rclcpp::ParameterValue(true));
8787
node->get_parameter(name + ".allow_unknown", allow_unknown_);
88+
declare_parameter_if_not_declared(
89+
node, name + ".use_final_approach_orientation", rclcpp::ParameterValue(false));
90+
node->get_parameter(name + ".use_final_approach_orientation", use_final_approach_orientation_);
8891

8992
// Create a planner based on the new costmap size
9093
planner_ = std::make_unique<NavFn>(
@@ -144,12 +147,40 @@ nav_msgs::msg::Path NavfnPlanner::createPlan(
144147

145148
nav_msgs::msg::Path path;
146149

150+
// Corner case of the start(x,y) = goal(x,y)
151+
if (start.pose.position.x == goal.pose.position.x &&
152+
start.pose.position.y == goal.pose.position.y)
153+
{
154+
unsigned int mx, my;
155+
costmap_->worldToMap(start.pose.position.x, start.pose.position.y, mx, my);
156+
if (costmap_->getCost(mx, my) == nav2_costmap_2d::LETHAL_OBSTACLE) {
157+
RCLCPP_WARN(logger_, "Failed to create a unique pose path because of obstacles");
158+
return path;
159+
}
160+
path.header.stamp = clock_->now();
161+
path.header.frame_id = global_frame_;
162+
geometry_msgs::msg::PoseStamped pose;
163+
pose.header = path.header;
164+
pose.pose.position.z = 0.0;
165+
166+
pose.pose = start.pose;
167+
// if we have a different start and goal orientation, set the unique path pose to the goal
168+
// orientation, unless use_final_approach_orientation=true where we need it to be the start
169+
// orientation to avoid movement from the local planner
170+
if (start.pose.orientation != goal.pose.orientation && !use_final_approach_orientation_) {
171+
pose.pose.orientation = goal.pose.orientation;
172+
}
173+
path.poses.push_back(pose);
174+
return path;
175+
}
176+
147177
if (!makePlan(start.pose, goal.pose, tolerance_, path)) {
148178
RCLCPP_WARN(
149179
logger_, "%s: failed to create plan with "
150180
"tolerance %.2f.", name_.c_str(), tolerance_);
151181
}
152182

183+
153184
#ifdef BENCHMARK_TESTING
154185
steady_clock::time_point b = steady_clock::now();
155186
duration<double> time_span = duration_cast<duration<double>>(b - a);
@@ -284,6 +315,32 @@ NavfnPlanner::makePlan(
284315
// extract the plan
285316
if (getPlanFromPotential(best_pose, plan)) {
286317
smoothApproachToGoal(best_pose, plan);
318+
319+
// If use_final_approach_orientation=true, interpolate the last pose orientation from the
320+
// previous pose to set the orientation to the 'final approach' orientation of the robot so
321+
// it does not rotate.
322+
// And deal with corner case of plan of length 1
323+
if (use_final_approach_orientation_) {
324+
size_t plan_size = plan.poses.size();
325+
if (plan_size == 1) {
326+
plan.poses.back().pose.orientation = start.orientation;
327+
} else if (plan_size > 1) {
328+
double dx, dy, theta;
329+
auto last_pose = plan.poses.back().pose.position;
330+
auto approach_pose = plan.poses[plan_size - 2].pose.position;
331+
// Deal with the case of NavFn producing a path with two equal last poses
332+
if (std::abs(last_pose.x - approach_pose.x) < 0.0001 &&
333+
std::abs(last_pose.y - approach_pose.y) < 0.0001 && plan_size > 2)
334+
{
335+
approach_pose = plan.poses[plan_size - 3].pose.position;
336+
}
337+
dx = last_pose.x - approach_pose.x;
338+
dy = last_pose.y - approach_pose.y;
339+
theta = atan2(dy, dx);
340+
plan.poses.back().pose.orientation =
341+
nav2_util::geometry_utils::orientationAroundZAxis(theta);
342+
}
343+
}
287344
} else {
288345
RCLCPP_ERROR(
289346
logger_,
@@ -489,6 +546,8 @@ NavfnPlanner::on_parameter_event_callback(
489546
use_astar_ = value.bool_value;
490547
} else if (name == name_ + ".allow_unknown") {
491548
allow_unknown_ = value.bool_value;
549+
} else if (name == name_ + ".use_final_approach_orientation") {
550+
use_final_approach_orientation_ = value.bool_value;
492551
}
493552
}
494553
}

nav2_smac_planner/include/nav2_smac_planner/smac_planner_2d.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -110,6 +110,7 @@ class SmacPlanner2D : public nav2_core::GlobalPlanner
110110
bool _allow_unknown;
111111
int _max_iterations;
112112
int _max_on_approach_iterations;
113+
bool _use_final_approach_orientation;
113114
SearchInfo _search_info;
114115
std::string _motion_model_for_search;
115116
MotionModel _motion_model;

nav2_smac_planner/src/smac_planner_2d.cpp

Lines changed: 52 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,7 @@
1919
#include <algorithm>
2020

2121
#include "nav2_smac_planner/smac_planner_2d.hpp"
22+
#include "nav2_util/geometry_utils.hpp"
2223

2324
// #define BENCHMARK_TESTING
2425

@@ -80,6 +81,9 @@ void SmacPlanner2D::configure(
8081
nav2_util::declare_parameter_if_not_declared(
8182
node, name + ".max_on_approach_iterations", rclcpp::ParameterValue(1000));
8283
node->get_parameter(name + ".max_on_approach_iterations", _max_on_approach_iterations);
84+
nav2_util::declare_parameter_if_not_declared(
85+
node, name + ".use_final_approach_orientation", rclcpp::ParameterValue(false));
86+
node->get_parameter(name + ".use_final_approach_orientation", _use_final_approach_orientation);
8387

8488
nav2_util::declare_parameter_if_not_declared(
8589
node, name + ".max_planning_time", rclcpp::ParameterValue(1.0));
@@ -218,13 +222,13 @@ nav_msgs::msg::Path SmacPlanner2D::createPlan(
218222
_a_star->setCollisionChecker(&_collision_checker);
219223

220224
// Set starting point
221-
unsigned int mx, my;
222-
costmap->worldToMap(start.pose.position.x, start.pose.position.y, mx, my);
223-
_a_star->setStart(mx, my, 0);
225+
unsigned int mx_start, my_start, mx_goal, my_goal;
226+
costmap->worldToMap(start.pose.position.x, start.pose.position.y, mx_start, my_start);
227+
_a_star->setStart(mx_start, my_start, 0);
224228

225229
// Set goal point
226-
costmap->worldToMap(goal.pose.position.x, goal.pose.position.y, mx, my);
227-
_a_star->setGoal(mx, my, 0);
230+
costmap->worldToMap(goal.pose.position.x, goal.pose.position.y, mx_goal, my_goal);
231+
_a_star->setGoal(mx_goal, my_goal, 0);
228232

229233
// Setup message
230234
nav_msgs::msg::Path plan;
@@ -238,6 +242,23 @@ nav_msgs::msg::Path SmacPlanner2D::createPlan(
238242
pose.pose.orientation.z = 0.0;
239243
pose.pose.orientation.w = 1.0;
240244

245+
// Corner case of start and goal beeing on the same cell
246+
if (mx_start == mx_goal && my_start == my_goal) {
247+
if (costmap->getCost(mx_start, my_start) == nav2_costmap_2d::LETHAL_OBSTACLE) {
248+
RCLCPP_WARN(_logger, "Failed to create a unique pose path because of obstacles");
249+
return plan;
250+
}
251+
pose.pose = start.pose;
252+
// if we have a different start and goal orientation, set the unique path pose to the goal
253+
// orientation, unless use_final_approach_orientation=true where we need it to be the start
254+
// orientation to avoid movement from the local planner
255+
if (start.pose.orientation != goal.pose.orientation && !_use_final_approach_orientation) {
256+
pose.pose.orientation = goal.pose.orientation;
257+
}
258+
plan.poses.push_back(pose);
259+
return plan;
260+
}
261+
241262
// Compute plan
242263
Node2D::CoordinateVector path;
243264
int num_iterations = 0;
@@ -292,6 +313,30 @@ nav_msgs::msg::Path SmacPlanner2D::createPlan(
292313
_smoother->smooth(plan, costmap, time_remaining);
293314
}
294315

316+
317+
// If use_final_approach_orientation=true, interpolate the last pose orientation from the
318+
// previous pose to set the orientation to the 'final approach' orientation of the robot so
319+
// it does not rotate.
320+
// And deal with corner case of plan of length 1
321+
// If use_final_approach_orientation=false (default), override last pose orientation to match goal
322+
size_t plan_size = plan.poses.size();
323+
if (_use_final_approach_orientation) {
324+
if (plan_size == 1) {
325+
plan.poses.back().pose.orientation = start.pose.orientation;
326+
} else if (plan_size > 1) {
327+
double dx, dy, theta;
328+
auto last_pose = plan.poses.back().pose.position;
329+
auto approach_pose = plan.poses[plan_size - 2].pose.position;
330+
dx = last_pose.x - approach_pose.x;
331+
dy = last_pose.y - approach_pose.y;
332+
theta = atan2(dy, dx);
333+
plan.poses.back().pose.orientation =
334+
nav2_util::geometry_utils::orientationAroundZAxis(theta);
335+
}
336+
} else if (plan_size > 0) {
337+
plan.poses.back().pose.orientation = goal.pose.orientation;
338+
}
339+
295340
return plan;
296341
}
297342

@@ -324,6 +369,8 @@ void SmacPlanner2D::on_parameter_event_callback(
324369
} else if (name == _name + ".allow_unknown") {
325370
reinit_a_star = true;
326371
_allow_unknown = value.bool_value;
372+
} else if (name == _name + ".use_final_approach_orientation") {
373+
_use_final_approach_orientation = value.bool_value;
327374
}
328375
} else if (type == ParameterType::PARAMETER_INTEGER) {
329376
if (name == _name + ".downsampling_factor") {

nav2_system_tests/src/planning/CMakeLists.txt

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -46,11 +46,11 @@ ament_add_test(test_planner_random
4646
TEST_MAP=${PROJECT_SOURCE_DIR}/maps/map.pgm
4747
)
4848

49-
ament_add_gtest(test_planner_plugin_failures
49+
ament_add_gtest(test_planner_plugins
5050
test_planner_plugins.cpp
5151
)
5252

53-
ament_target_dependencies(test_planner_plugin_failures rclcpp geometry_msgs nav2_msgs ${dependencies})
54-
target_link_libraries(test_planner_plugin_failures
53+
ament_target_dependencies(test_planner_plugins rclcpp geometry_msgs nav2_msgs ${dependencies})
54+
target_link_libraries(test_planner_plugins
5555
stdc++fs
5656
)

nav2_system_tests/src/planning/test_planner_plugins.cpp

Lines changed: 130 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
#include "rclcpp/rclcpp.hpp"
2121
#include "planner_tester.hpp"
2222
#include "nav2_util/lifecycle_utils.hpp"
23+
#include "nav2_util/geometry_utils.hpp"
2324

2425
using namespace std::chrono_literals;
2526

@@ -33,6 +34,60 @@ void callback(const nav_msgs::msg::Path::ConstSharedPtr /*grid*/)
3334
{
3435
}
3536

37+
void testSmallPathValidityAndOrientation(std::string plugin, double length)
38+
{
39+
auto obj = std::make_shared<nav2_system_tests::NavFnPlannerTester>();
40+
rclcpp_lifecycle::State state;
41+
obj->set_parameter(rclcpp::Parameter("GridBased.plugin", plugin));
42+
obj->declare_parameter(
43+
"GridBased.use_final_approach_orientation", rclcpp::ParameterValue(false));
44+
obj->onConfigure(state);
45+
46+
geometry_msgs::msg::PoseStamped start;
47+
geometry_msgs::msg::PoseStamped goal;
48+
49+
start.pose.position.x = 0.5;
50+
start.pose.position.y = 0.5;
51+
start.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(M_PI_2);
52+
start.header.frame_id = "map";
53+
54+
goal.pose.position.x = 0.5;
55+
goal.pose.position.y = start.pose.position.y + length;
56+
goal.pose.orientation = nav2_util::geometry_utils::orientationAroundZAxis(-M_PI);
57+
goal.header.frame_id = "map";
58+
59+
// Test without use_final_approach_orientation
60+
// expecting end path pose orientation to be equal to goal orientation
61+
auto path = obj->getPlan(start, goal, "GridBased");
62+
EXPECT_GT((int)path.poses.size(), 0);
63+
EXPECT_NEAR(tf2::getYaw(path.poses.back().pose.orientation), -M_PI, 0.01);
64+
obj->onCleanup(state);
65+
66+
// Test WITH use_final_approach_orientation
67+
// expecting end path pose orientation to be equal to approach orientation
68+
// which in the one pose corner case should be the start pose orientation
69+
obj->set_parameter(rclcpp::Parameter("GridBased.use_final_approach_orientation", true));
70+
obj->onConfigure(state);
71+
path = obj->getPlan(start, goal, "GridBased");
72+
EXPECT_GT((int)path.poses.size(), 0);
73+
74+
int path_size = path.poses.size();
75+
if (path_size == 1) {
76+
EXPECT_NEAR(
77+
tf2::getYaw(path.poses.back().pose.orientation),
78+
tf2::getYaw(start.pose.orientation),
79+
0.01);
80+
} else {
81+
double dx = path.poses.back().pose.position.x - path.poses.front().pose.position.x;
82+
double dy = path.poses.back().pose.position.y - path.poses.front().pose.position.y;
83+
EXPECT_NEAR(
84+
tf2::getYaw(path.poses.back().pose.orientation),
85+
atan2(dy, dx),
86+
0.01);
87+
}
88+
obj->onCleanup(state);
89+
}
90+
3691
TEST(testPluginMap, Failures)
3792
{
3893
auto obj = std::make_shared<nav2_system_tests::NavFnPlannerTester>();
@@ -55,6 +110,81 @@ TEST(testPluginMap, Failures)
55110
obj->onCleanup(state);
56111
}
57112

113+
TEST(testPluginMap, Smac2dEqualStartGoal)
114+
{
115+
testSmallPathValidityAndOrientation("nav2_smac_planner/SmacPlanner2D", 0.0);
116+
}
117+
118+
TEST(testPluginMap, Smac2dVerySmallPath)
119+
{
120+
testSmallPathValidityAndOrientation("nav2_smac_planner/SmacPlanner2D", 0.00001);
121+
}
122+
123+
TEST(testPluginMap, Smac2dBelowCostmapResolution)
124+
{
125+
testSmallPathValidityAndOrientation("nav2_smac_planner/SmacPlanner2D", 0.09);
126+
}
127+
128+
TEST(testPluginMap, Smac2dJustAboveCostmapResolution)
129+
{
130+
testSmallPathValidityAndOrientation("nav2_smac_planner/SmacPlanner2D", 0.102);
131+
}
132+
133+
TEST(testPluginMap, Smac2dAboveCostmapResolution)
134+
{
135+
testSmallPathValidityAndOrientation("nav2_smac_planner/SmacPlanner2D", 1.5);
136+
}
137+
138+
TEST(testPluginMap, NavFnEqualStartGoal)
139+
{
140+
testSmallPathValidityAndOrientation("nav2_navfn_planner/NavfnPlanner", 0.0);
141+
}
142+
143+
TEST(testPluginMap, NavFnVerySmallPath)
144+
{
145+
testSmallPathValidityAndOrientation("nav2_navfn_planner/NavfnPlanner", 0.00001);
146+
}
147+
148+
TEST(testPluginMap, NavFnBelowCostmapResolution)
149+
{
150+
testSmallPathValidityAndOrientation("nav2_navfn_planner/NavfnPlanner", 0.09);
151+
}
152+
153+
TEST(testPluginMap, NavFnJustAboveCostmapResolution)
154+
{
155+
testSmallPathValidityAndOrientation("nav2_navfn_planner/NavfnPlanner", 0.102);
156+
}
157+
158+
TEST(testPluginMap, NavFnAboveCostmapResolution)
159+
{
160+
testSmallPathValidityAndOrientation("nav2_navfn_planner/NavfnPlanner", 1.5);
161+
}
162+
163+
TEST(testPluginMap, ThetaStarEqualStartGoal)
164+
{
165+
testSmallPathValidityAndOrientation("nav2_theta_star_planner/ThetaStarPlanner", 0.0);
166+
}
167+
168+
TEST(testPluginMap, ThetaStarVerySmallPath)
169+
{
170+
testSmallPathValidityAndOrientation("nav2_theta_star_planner/ThetaStarPlanner", 0.00001);
171+
}
172+
173+
TEST(testPluginMap, ThetaStarBelowCostmapResolution)
174+
{
175+
testSmallPathValidityAndOrientation("nav2_theta_star_planner/ThetaStarPlanner", 0.09);
176+
}
177+
178+
TEST(testPluginMap, ThetaStarJustAboveCostmapResolution)
179+
{
180+
testSmallPathValidityAndOrientation("nav2_theta_star_planner/ThetaStarPlanner", 0.102);
181+
}
182+
183+
TEST(testPluginMap, ThetaStarAboveCostmapResolution)
184+
{
185+
testSmallPathValidityAndOrientation("nav2_theta_star_planner/ThetaStarPlanner", 1.5);
186+
}
187+
58188
int main(int argc, char ** argv)
59189
{
60190
::testing::InitGoogleTest(&argc, argv);

0 commit comments

Comments
 (0)