Skip to content

Commit b48ba73

Browse files
Adding Simple Path Smoother Plugin (#2875)
* adding new smoother plugin for simple smoothing needs * refining test cases * finish simple smoother tests * smoother server plugin working + add to params file
1 parent ad34693 commit b48ba73

File tree

12 files changed

+804
-34
lines changed

12 files changed

+804
-34
lines changed

‎nav2_bringup/params/nav2_params.yaml‎

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -300,6 +300,12 @@ planner_server_rclcpp_node:
300300
smoother_server:
301301
ros__parameters:
302302
use_sim_time: True
303+
smoother_plugins: ["simple_smoother"]
304+
simple_smoother:
305+
plugin: "nav2_smoother::SimpleSmoother"
306+
tolerance: 1.0e-10
307+
max_its: 1000
308+
do_refinement: True
303309

304310
recoveries_server:
305311
ros__parameters:

‎nav2_core/include/nav2_core/smoother.hpp‎

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,6 @@ class Smoother
4040
public:
4141
using Ptr = std::shared_ptr<nav2_core::Smoother>;
4242

43-
4443
/**
4544
* @brief Virtual destructor
4645
*/

‎nav2_costmap_2d/include/nav2_costmap_2d/cost_values.hpp‎

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -42,6 +42,7 @@ namespace nav2_costmap_2d
4242
static constexpr unsigned char NO_INFORMATION = 255;
4343
static constexpr unsigned char LETHAL_OBSTACLE = 254;
4444
static constexpr unsigned char INSCRIBED_INFLATED_OBSTACLE = 253;
45+
static constexpr unsigned char MAX_NON_OBSTACLE = 252;
4546
static constexpr unsigned char FREE_SPACE = 0;
4647
}
4748
#endif // NAV2_COSTMAP_2D__COST_VALUES_HPP_

‎nav2_costmap_2d/include/nav2_costmap_2d/costmap_subscriber.hpp‎

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -56,7 +56,6 @@ class CostmapSubscriber
5656
*/
5757
std::shared_ptr<Costmap2D> getCostmap();
5858

59-
protected:
6059
/**
6160
* @brief Convert an occ grid message into a costmap object
6261
*/
@@ -66,6 +65,7 @@ class CostmapSubscriber
6665
*/
6766
void costmapCallback(const nav2_msgs::msg::Costmap::SharedPtr msg);
6867

68+
protected:
6969
std::shared_ptr<Costmap2D> costmap_;
7070
nav2_msgs::msg::Costmap::SharedPtr costmap_msg_;
7171
std::string topic_name_;

‎nav2_smoother/CMakeLists.txt‎

Lines changed: 24 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -26,17 +26,8 @@ include_directories(
2626
)
2727

2828
set(executable_name smoother_server)
29-
30-
add_executable(${executable_name}
31-
src/main.cpp
32-
)
33-
3429
set(library_name ${executable_name}_core)
3530

36-
add_library(${library_name} SHARED
37-
src/nav2_smoother.cpp
38-
)
39-
4031
set(dependencies
4132
angles
4233
rclcpp
@@ -51,10 +42,32 @@ set(dependencies
5142
pluginlib
5243
)
5344

45+
# Main library
46+
add_library(${library_name} SHARED
47+
src/nav2_smoother.cpp
48+
)
5449
ament_target_dependencies(${library_name}
5550
${dependencies}
5651
)
5752

53+
# Main executable
54+
add_executable(${executable_name}
55+
src/main.cpp
56+
)
57+
ament_target_dependencies(${executable_name}
58+
${dependencies}
59+
)
60+
target_link_libraries(${executable_name} ${library_name})
61+
62+
# Simple Smoother plugin
63+
add_library(simple_smoother SHARED
64+
src/simple_smoother.cpp
65+
)
66+
ament_target_dependencies(simple_smoother
67+
${dependencies}
68+
)
69+
pluginlib_export_plugin_description_file(nav2_core plugins.xml)
70+
5871
if(BUILD_TESTING)
5972
find_package(ament_lint_auto REQUIRED)
6073
# the following line skips the linter which checks for copyrights
@@ -64,17 +77,10 @@ if(BUILD_TESTING)
6477
find_package(ament_cmake_gtest REQUIRED)
6578
endif()
6679

67-
ament_target_dependencies(${executable_name}
68-
${dependencies}
69-
)
70-
71-
target_link_libraries(${executable_name} ${library_name})
72-
7380
rclcpp_components_register_nodes(${library_name} "nav2_smoother::SmootherServer")
7481

7582
install(
76-
TARGETS
77-
${library_name}
83+
TARGETS ${library_name} simple_smoother
7884
ARCHIVE DESTINATION lib
7985
LIBRARY DESTINATION lib
8086
RUNTIME DESTINATION bin
@@ -96,8 +102,6 @@ if(BUILD_TESTING)
96102
endif()
97103

98104
ament_export_include_directories(include)
99-
ament_export_libraries(
100-
${library_name})
105+
ament_export_libraries(${library_name} simple_smoother)
101106
ament_export_dependencies(${dependencies})
102-
103107
ament_package()
Lines changed: 161 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,161 @@
1+
// Copyright (c) 2022, Samsung Research America
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+
#ifndef NAV2_SMOOTHER__SIMPLE_SMOOTHER_HPP_
16+
#define NAV2_SMOOTHER__SIMPLE_SMOOTHER_HPP_
17+
18+
#include <cmath>
19+
#include <vector>
20+
#include <string>
21+
#include <iostream>
22+
#include <memory>
23+
#include <queue>
24+
#include <utility>
25+
26+
#include "nav2_core/smoother.hpp"
27+
#include "nav2_costmap_2d/costmap_2d.hpp"
28+
#include "nav2_costmap_2d/cost_values.hpp"
29+
#include "nav2_util/geometry_utils.hpp"
30+
#include "nav2_util/node_utils.hpp"
31+
#include "nav_msgs/msg/path.hpp"
32+
#include "angles/angles.h"
33+
#include "tf2/utils.h"
34+
35+
namespace nav2_smoother
36+
{
37+
38+
/**
39+
* @class nav2_smoother::PathSegment
40+
* @brief A segment of a path in start/end indices
41+
*/
42+
struct PathSegment
43+
{
44+
unsigned int start;
45+
unsigned int end;
46+
};
47+
48+
typedef std::vector<geometry_msgs::msg::PoseStamped>::iterator PathIterator;
49+
typedef std::vector<geometry_msgs::msg::PoseStamped>::reverse_iterator ReversePathIterator;
50+
51+
/**
52+
* @class nav2_smoother::SimpleSmoother
53+
* @brief A path smoother implementation
54+
*/
55+
class SimpleSmoother : public nav2_core::Smoother
56+
{
57+
public:
58+
/**
59+
* @brief A constructor for nav2_smoother::SimpleSmoother
60+
*/
61+
SimpleSmoother() = default;
62+
63+
/**
64+
* @brief A destructor for nav2_smoother::SimpleSmoother
65+
*/
66+
~SimpleSmoother() override = default;
67+
68+
void configure(
69+
const rclcpp_lifecycle::LifecycleNode::WeakPtr &,
70+
std::string name, const std::shared_ptr<tf2_ros::Buffer> &,
71+
const std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> &,
72+
const std::shared_ptr<nav2_costmap_2d::FootprintSubscriber> &) override;
73+
74+
/**
75+
* @brief Method to cleanup resources.
76+
*/
77+
void cleanup() override {costmap_sub_.reset();}
78+
79+
/**
80+
* @brief Method to activate smoother and any threads involved in execution.
81+
*/
82+
void activate() override {}
83+
84+
/**
85+
* @brief Method to deactivate smoother and any threads involved in execution.
86+
*/
87+
void deactivate() override {}
88+
89+
/**
90+
* @brief Method to smooth given path
91+
*
92+
* @param path In-out path to be smoothed
93+
* @param max_time Maximum duration smoothing should take
94+
* @return If smoothing was completed (true) or interrupted by time limit (false)
95+
*/
96+
bool smooth(
97+
nav_msgs::msg::Path & path,
98+
const rclcpp::Duration & max_time) override;
99+
100+
protected:
101+
/**
102+
* @brief Smoother method - does the smoothing on a segment
103+
* @param path Reference to path
104+
* @param reversing_segment Return if this is a reversing segment
105+
* @param costmap Pointer to minimal costmap
106+
* @param max_time Maximum time to compute, stop early if over limit
107+
* @return If smoothing was successful
108+
*/
109+
bool smoothImpl(
110+
nav_msgs::msg::Path & path,
111+
bool & reversing_segment,
112+
const nav2_costmap_2d::Costmap2D * costmap,
113+
const double & max_time);
114+
115+
/**
116+
* @brief Get the field value for a given dimension
117+
* @param msg Current pose to sample
118+
* @param dim Dimension ID of interest
119+
* @return dim value
120+
*/
121+
inline double getFieldByDim(
122+
const geometry_msgs::msg::PoseStamped & msg,
123+
const unsigned int & dim);
124+
125+
/**
126+
* @brief Set the field value for a given dimension
127+
* @param msg Current pose to sample
128+
* @param dim Dimension ID of interest
129+
* @param value to set the dimention to for the pose
130+
*/
131+
inline void setFieldByDim(
132+
geometry_msgs::msg::PoseStamped & msg, const unsigned int dim,
133+
const double & value);
134+
135+
/**
136+
* @brief Finds the starting and end indices of path segments where
137+
* the robot is traveling in the same direction (e.g. forward vs reverse)
138+
* @param path Path in which to look for cusps
139+
* @return Set of index pairs for each segment of the path in a given direction
140+
*/
141+
std::vector<PathSegment> findDirectionalPathSegments(const nav_msgs::msg::Path & path);
142+
143+
/**
144+
* @brief For a given path, update the path point orientations based on smoothing
145+
* @param path Path to approximate the path orientation in
146+
* @param reversing_segment Return if this is a reversing segment
147+
*/
148+
inline void updateApproximatePathOrientations(
149+
nav_msgs::msg::Path & path,
150+
bool & reversing_segment);
151+
152+
double tolerance_, data_w_, smooth_w_;
153+
int max_its_, refinement_ctr_;
154+
bool do_refinement_;
155+
std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub_;
156+
rclcpp::Logger logger_{rclcpp::get_logger("SimpleSmoother")};
157+
};
158+
159+
} // namespace nav2_smoother
160+
161+
#endif // NAV2_SMOOTHER__SIMPLE_SMOOTHER_HPP_

‎nav2_smoother/plugins.xml‎

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
<class_libraries>
2+
<library path="simple_smoother">
3+
<class type="nav2_smoother::SimpleSmoother" base_class_type="nav2_core::Smoother">
4+
<description>Does a simple smoothing process with collision checking</description>
5+
</class>
6+
</library>
7+
</class_libraries>

‎nav2_smoother/src/nav2_smoother.cpp‎

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -36,8 +36,8 @@ namespace nav2_smoother
3636
SmootherServer::SmootherServer(const rclcpp::NodeOptions & options)
3737
: LifecycleNode("smoother_server", "", false, options),
3838
lp_loader_("nav2_core", "nav2_core::Smoother"),
39-
default_ids_{}, default_types_{
40-
"nav2_smoother::CeresCostawareSmoother"}
39+
default_ids_{"simple_smoother"},
40+
default_types_{"nav2_smoother::SimpleSmoother"}
4141
{
4242
RCLCPP_INFO(get_logger(), "Creating smoother server");
4343

0 commit comments

Comments
 (0)