Skip to content
Merged
Show file tree
Hide file tree
Changes from 47 commits
Commits
Show all changes
48 commits
Select commit Hold shift + click to select a range
b2f9d6d
added edge length method
alexanderjyuen Apr 16, 2025
d198fa8
Added corner arc class
alexanderjyuen May 30, 2025
8cb47e0
replaced double vectors with Coordinates, added methods to return sta…
alexanderjyuen May 30, 2025
88b1648
using Coordinates, fixed direction of tangents
alexanderjyuen May 30, 2025
c4dc85d
added corner arc in header, added logger in protected variable
alexanderjyuen May 30, 2025
815d88c
first pass of corner smoothing algorithm
alexanderjyuen May 30, 2025
537cf97
reassigning next edge to have a different start, if a corner occurs b…
alexanderjyuen Jun 2, 2025
e623d9d
using unique pointer instead of raw pointers for new edges and nodes
alexanderjyuen Jun 2, 2025
66eee22
added smoothing parameter
alexanderjyuen Jun 2, 2025
d33bc2d
made angle of interpolation a parameter
alexanderjyuen Jun 2, 2025
6c1b2b6
const for return methods, added flag for smoothing corners
alexanderjyuen Jun 2, 2025
9cac954
moved getEdgeLength() into the Directional Edge struct
alexanderjyuen Jun 3, 2025
2c96ceb
using float instead of double
alexanderjyuen Jun 4, 2025
d4bd9dc
smoothing radius is float, couple methods moved to protected
alexanderjyuen Jun 4, 2025
752ff04
removed signed_angle_ as a member variable
alexanderjyuen Jun 4, 2025
690ad2a
removed unnecessary member variables
alexanderjyuen Jun 4, 2025
7dc35f8
removed angle of interpolation and inferring it from path density and…
alexanderjyuen Jun 4, 2025
2626b6a
consolidated corner arc into one header function
alexanderjyuen Jun 4, 2025
5d6d37d
readded newline
alexanderjyuen Jun 4, 2025
4f7bba1
changed corner arc to corner smoothing
alexanderjyuen Jun 4, 2025
4d6b8e0
replaced the use of edges with coordinates to generate smoothing arc,…
alexanderjyuen Jun 4, 2025
f0dff73
linting
alexanderjyuen Jun 4, 2025
53f2209
fixing cpplint
alexanderjyuen Jun 4, 2025
5b0b709
linting for headers
alexanderjyuen Jun 4, 2025
c827e52
cpplinting
alexanderjyuen Jun 4, 2025
d46468f
Update nav2_route/src/path_converter.cpp
SteveMacenski Jun 5, 2025
edbe42a
Update nav2_route/src/path_converter.cpp
SteveMacenski Jun 5, 2025
46ca874
Update nav2_route/src/path_converter.cpp
SteveMacenski Jun 5, 2025
68befab
Update nav2_route/src/path_converter.cpp
SteveMacenski Jun 5, 2025
e9a1882
Update nav2_route/include/nav2_route/corner_smoothing.hpp
SteveMacenski Jun 5, 2025
9555c93
fixed divide by zeros and accessing empty route.edges
alexanderjyuen Jun 6, 2025
b3cf20a
Merge branch 'route_server_corner_smoothing' of github.com:alexanderj…
alexanderjyuen Jun 6, 2025
5a39b87
uncrustify linting
alexanderjyuen Jun 6, 2025
752d1f2
cpp linting
alexanderjyuen Jun 6, 2025
b41c896
path converter linting
alexanderjyuen Jun 6, 2025
2024731
changed all doubles to floats
alexanderjyuen Jun 9, 2025
ee16acb
added check for edges that are colinear to avoid divide by 0, fixed f…
alexanderjyuen Jun 11, 2025
4e5baaf
linting
alexanderjyuen Jun 11, 2025
cc2114a
Update nav2_route/include/nav2_route/corner_smoothing.hpp
SteveMacenski Jun 11, 2025
1ce133e
added doxygen for corner arc class
alexanderjyuen Jun 11, 2025
9dafb46
Merge branch 'route_server_corner_smoothing' of github.com:alexanderj…
alexanderjyuen Jun 11, 2025
1728030
added warning message if corner can't be smoothed
alexanderjyuen Jun 11, 2025
55d54ec
added smooth_corners to the nav2 params file
alexanderjyuen Jun 11, 2025
989d092
added smoothing flag and radius parameter to README.md'
alexanderjyuen Jun 11, 2025
7e3e547
typo in README
alexanderjyuen Jun 11, 2025
dfff167
added testing for corner smoothing
alexanderjyuen Jun 11, 2025
0a7fa13
Merge branch 'main' into route_server_corner_smoothing
alexanderjyuen Jun 12, 2025
b2903a4
Update nav2_route/include/nav2_route/corner_smoothing.hpp
SteveMacenski Jun 12, 2025
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions nav2_bringup/params/nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -447,6 +447,7 @@ route_server:
# graph_filepath: $(find-pkg-share nav2_route)/graphs/aws_graph.geojson
boundary_radius_to_achieve_node: 1.0
radius_to_achieve_node: 2.0
smooth_corners: true
operations: ["AdjustSpeedLimit", "ReroutingService", "CollisionMonitor"]
ReroutingService:
plugin: "nav2_route::ReroutingService"
Expand Down
2 changes: 2 additions & 0 deletions nav2_route/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -114,6 +114,8 @@ route_server:
path_density: 0.05 # Density of points for generating the dense nav_msgs/Path from route (m)
max_iterations: 0 # Maximum number of search iterations, if 0, uses maximum possible
max_planning_time: 2.0 # Maximum planning time (seconds)
smooth_corners: true # Whether to smooth corners formed by adjacent edges or not
smoothing_radius: 1.0 # Radius of corner to fit into the corner
costmap_topic: 'global_costmap/costmap_raw' # Costmap topic when enable_nn_search is enabled. May also be used by the collision monitor operation and/or the costmap edge scorer if using the same topic to share resources.

graph_file_loader: "GeoJsonGraphFileLoader" # Name of default file loader
Expand Down
171 changes: 171 additions & 0 deletions nav2_route/include/nav2_route/corner_smoothing.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,171 @@
// Copyright (c) 2025, Polymath Robotics
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef NAV2_ROUTE__CORNER_SMOOTHING_HPP_
#define NAV2_ROUTE__CORNER_SMOOTHING_HPP_

#include <vector>
#include <cmath>
#include <algorithm>

#include "nav2_route/types.hpp"
#include "nav2_route/utils.hpp"

namespace nav2_route
{
/**
* @class nav2_route::CornerArc
* @brief A class used to smooth corners defined by the edges and nodes
* of the route graph. Used with path converter to output a corner smoothed plan
*/
class CornerArc
{
public:
/**
* @brief A constructor for nav2_route::CornerArc
* @param start start coordinate of corner to be smoothed
* @param corner corner coordinate of corner to be smoothed
* @param end end coordinate of corner to be smoothed
* @param minimum_radius smoothing radius to fit to the corner
*/
CornerArc(
const Coordinates & start, const Coordinates & corner, const Coordinates & end,
float minimum_radius)
{
start_edge_length_ = hypotf(corner.x - start.x, corner.y - start.y);
end_edge_length_ = hypotf(end.x - corner.x, end.y - corner.y);

// invalid scenario would cause equations to blow up
if (start_edge_length_ == 0.0 || end_edge_length_ == 0.0) {return;}

float angle = getAngleBetweenEdges(start, corner, end);

// cannot smooth a 0 (back and forth) or 180 (straight line) angle
if (std::abs(angle) < 1E-6 || std::abs(angle - M_PI) < 1E-6) {return;}

float tangent_length = minimum_radius / (std::tan(std::fabs(angle) / 2));

if (tangent_length < start_edge_length_ && tangent_length < end_edge_length_) {
std::vector<float> start_edge_unit_tangent =
{(start.x - corner.x) / start_edge_length_, (start.y - corner.y) / start_edge_length_};
std::vector<float> end_edge_unit_tangent =
{(end.x - corner.x) / end_edge_length_, (end.y - corner.y) / end_edge_length_};

float bisector_x = start_edge_unit_tangent[0] + end_edge_unit_tangent[0];
float bisector_y = start_edge_unit_tangent[1] + end_edge_unit_tangent[1];
float bisector_magnitude = std::sqrt(bisector_x * bisector_x + bisector_y * bisector_y);

std::vector<float> unit_bisector =
{bisector_x / bisector_magnitude, bisector_y / bisector_magnitude};

start_coordinate_.x = corner.x + start_edge_unit_tangent[0] * tangent_length;
start_coordinate_.y = corner.y + start_edge_unit_tangent[1] * tangent_length;

end_coordinate_.x = corner.x + end_edge_unit_tangent[0] * tangent_length;
end_coordinate_.y = corner.y + end_edge_unit_tangent[1] * tangent_length;

float bisector_length = minimum_radius / std::sin(angle / 2);

circle_center_coordinate_.x = corner.x + unit_bisector[0] * bisector_length;
circle_center_coordinate_.y = corner.y + unit_bisector[1] * bisector_length;

valid_corner_ = true;
}
}

/**
* @brief A destructor for nav2_route::CornerArc
*/
~CornerArc() = default;

void interpolateArc(
const float & max_angle_resolution,
std::vector<geometry_msgs::msg::PoseStamped> & poses)
{
std::vector<float> r_start{start_coordinate_.x - circle_center_coordinate_.x,
start_coordinate_.y - circle_center_coordinate_.y};
std::vector<float> r_end{end_coordinate_.x - circle_center_coordinate_.x,
end_coordinate_.y - circle_center_coordinate_.y};
float cross = r_start[0] * r_end[1] - r_start[1] * r_end[0];
float dot = r_start[0] * r_end[0] + r_start[1] * r_end[1];
float signed_angle = std::atan2(cross, dot);
// lower limit for N is 1 to protect against divide by 0
int N = std::max(1, static_cast<int>(std::ceil(std::abs(signed_angle) / max_angle_resolution)));
float angle_resolution = signed_angle / N;

float x, y;
for (int i = 0; i <= N; i++) {
float angle = i * angle_resolution;
x = circle_center_coordinate_.x +
(r_start[0] * std::cos(angle) - r_start[1] * std::sin(angle));
y = circle_center_coordinate_.y +
(r_start[0] * std::sin(angle) + r_start[1] * std::cos(angle));
poses.push_back(utils::toMsg(x, y));
}
}

/**
* @brief return if a valid corner arc (one that doesn't overrun the edge lengths) is generated
* @return if the a corner was able to be generated
*/
bool isCornerValid() const {return valid_corner_;}

/**
* @brief return the start coordinate of the corner arc
* @return start coordinate of the arc
*/
Coordinates getCornerStart() const {return start_coordinate_;}

/**
* @brief return the end coordinate of the corner arc
* @return end coordinate of the arc
*/
Coordinates getCornerEnd() const {return end_coordinate_;}

protected:
/**
* @brief find the signed angle between a corner generated by 3 points
* @param start start coordinate of corner to be smoothed
* @param corner corner coordinate of corner to be smoothed
* @param end end coordinate of corner to be smoothed
* @return signed angle of the corner
*/
float getAngleBetweenEdges(
const Coordinates & start, const Coordinates & corner,
const Coordinates & end)
{
float start_dx = start.x - corner.x;
float start_dy = start.y - corner.y;

float end_dx = end.x - corner.x;
float end_dy = end.y - corner.y;

float angle =
acos((start_dx * end_dx + start_dy * end_dy) / (start_edge_length_ * end_edge_length_));

return angle;
}

private:
bool valid_corner_{false};
float start_edge_length_;
float end_edge_length_;
Coordinates start_coordinate_;
Coordinates end_coordinate_;
Coordinates circle_center_coordinate_;
};

} // namespace nav2_route

#endif // NAV2_ROUTE__CORNER_SMOOTHING_HPP_
4 changes: 4 additions & 0 deletions nav2_route/include/nav2_route/path_converter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
#include "nav2_util/node_utils.hpp"
#include "nav2_route/types.hpp"
#include "nav2_route/utils.hpp"
#include "nav2_route/corner_smoothing.hpp"

namespace nav2_route
{
Expand Down Expand Up @@ -80,7 +81,10 @@ class PathConverter

protected:
rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>::SharedPtr path_pub_;
rclcpp::Logger logger_{rclcpp::get_logger("PathConverter")};
float density_;
float smoothing_radius_;
bool smooth_corners_;
};

} // namespace nav2_route
Expand Down
9 changes: 9 additions & 0 deletions nav2_route/include/nav2_route/types.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -138,6 +138,8 @@ struct DirectionalEdge
EdgeCost edge_cost; // Cost information associated with edge
Metadata metadata; // Any metadata stored in the graph file of interest
Operations operations; // Operations to perform related to the edge

float getEdgeLength();
};

typedef DirectionalEdge * EdgePtr;
Expand Down Expand Up @@ -194,6 +196,13 @@ struct Node
}
};

inline float DirectionalEdge::getEdgeLength()
{
return hypotf(
end->coords.x - start->coords.x,
end->coords.y - start->coords.y);
}

/**
* @struct nav2_route::Route
* @brief An ordered set of nodes and edges corresponding to the planned route
Expand Down
52 changes: 46 additions & 6 deletions nav2_route/src/path_converter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,9 +30,16 @@ void PathConverter::configure(nav2_util::LifecycleNode::SharedPtr node)
nav2_util::declare_parameter_if_not_declared(
node, "path_density", rclcpp::ParameterValue(0.05));
density_ = static_cast<float>(node->get_parameter("path_density").as_double());
nav2_util::declare_parameter_if_not_declared(
node, "smoothing_radius", rclcpp::ParameterValue(1.0));
smoothing_radius_ = static_cast<float>(node->get_parameter("smoothing_radius").as_double());
nav2_util::declare_parameter_if_not_declared(
node, "smooth_corners", rclcpp::ParameterValue(false));
smooth_corners_ = node->get_parameter("smooth_corners").as_bool();

path_pub_ = node->create_publisher<nav_msgs::msg::Path>("plan", 1);
path_pub_->on_activate();
logger_ = node->get_logger();
}

nav_msgs::msg::Path PathConverter::densify(
Expand All @@ -54,17 +61,50 @@ nav_msgs::msg::Path PathConverter::densify(
interpolateEdge(start.x, start.y, end.x, end.y, path.poses);
}

// Fill in path via route edges
for (unsigned int i = 0; i != route.edges.size(); i++) {
const EdgePtr edge = route.edges[i];
const Coordinates & start = edge->start->coords;
const Coordinates & end = edge->end->coords;
interpolateEdge(start.x, start.y, end.x, end.y, path.poses);
Coordinates start;
Coordinates end;

if (!route.edges.empty()) {
start = route.edges[0]->start->coords;

// Fill in path via route edges
for (unsigned int i = 0; i < route.edges.size() - 1; i++) {
const EdgePtr edge = route.edges[i];
const EdgePtr & next_edge = route.edges[i + 1];
end = edge->end->coords;

CornerArc corner_arc(start, end, next_edge->end->coords, smoothing_radius_);
if (corner_arc.isCornerValid() && smooth_corners_) {
// if an arc exists, end of the first edge is the start of the arc
end = corner_arc.getCornerStart();

// interpolate to start of arc
interpolateEdge(start.x, start.y, end.x, end.y, path.poses);

// interpolate arc
corner_arc.interpolateArc(density_ / smoothing_radius_, path.poses);

// new start of next edge is end of smoothing arc
start = corner_arc.getCornerEnd();
} else {
if (smooth_corners_) {
RCLCPP_WARN(
logger_, "Unable to smooth corner between edge %i and edge %i", edge->edgeid,
next_edge->edgeid);
}
interpolateEdge(start.x, start.y, end.x, end.y, path.poses);
start = end;
}
}
}

if (route.edges.empty()) {
path.poses.push_back(utils::toMsg(route.start_node->coords.x, route.start_node->coords.y));
} else {
interpolateEdge(
start.x, start.y, route.edges.back()->end->coords.x,
route.edges.back()->end->coords.y, path.poses);

path.poses.push_back(
utils::toMsg(route.edges.back()->end->coords.x, route.edges.back()->end->coords.y));
}
Expand Down
8 changes: 8 additions & 0 deletions nav2_route/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -127,3 +127,11 @@ ament_add_gtest(test_goal_intent_search
target_link_libraries(test_goal_intent_search
${library_name}
)

# Test corner smoothing
ament_add_gtest(test_corner_smoothing
test_corner_smoothing.cpp
)
target_link_libraries(test_corner_smoothing
${library_name}
)
Loading
Loading