Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
smoother.hpp
1 // Copyright (c) 2021, 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_SMAC_PLANNER__SMOOTHER_HPP_
16 #define NAV2_SMAC_PLANNER__SMOOTHER_HPP_
17 
18 #include <vector>
19 
20 #include "nav2_costmap_2d/costmap_2d.hpp"
21 #include "nav2_smac_planner/types.hpp"
22 #include "nav2_smac_planner/constants.hpp"
23 #include "nav2_util/geometry_utils.hpp"
24 #include "nav_msgs/msg/path.hpp"
25 #include "ompl/base/StateSpace.h"
26 
27 namespace nav2_smac_planner
28 {
29 
35 {
36  unsigned int start;
37  unsigned int end;
38 };
39 
45 {
49  BoundaryPoints(double & x_in, double & y_in, double & theta_in)
50  : x(x_in), y(y_in), theta(theta_in)
51  {}
52 
53  double x;
54  double y;
55  double theta;
56 };
57 
63 {
64  double path_end_idx{0.0};
65  double expansion_path_length{0.0};
66  double original_path_length{0.0};
67  std::vector<BoundaryPoints> pts;
68  bool in_collision{false};
69 };
70 
71 typedef std::vector<BoundaryExpansion> BoundaryExpansions;
72 typedef std::vector<geometry_msgs::msg::PoseStamped>::iterator PathIterator;
73 typedef std::vector<geometry_msgs::msg::PoseStamped>::reverse_iterator ReversePathIterator;
74 
79 class Smoother
80 {
81 public:
85  explicit Smoother(const SmootherParams & params);
86 
90  ~Smoother() {}
91 
97  void initialize(
98  const double & min_turning_radius);
99 
107  bool smooth(
108  nav_msgs::msg::Path & path,
109  const nav2_costmap_2d::Costmap2D * costmap,
110  const double & max_time);
111 
112 protected:
121  bool smoothImpl(
122  nav_msgs::msg::Path & path,
123  bool & reversing_segment,
124  const nav2_costmap_2d::Costmap2D * costmap,
125  const double & max_time);
126 
133  inline double getFieldByDim(
134  const geometry_msgs::msg::PoseStamped & msg,
135  const unsigned int & dim);
136 
143  inline void setFieldByDim(
144  geometry_msgs::msg::PoseStamped & msg, const unsigned int dim,
145  const double & value);
146 
153  std::vector<PathSegment> findDirectionalPathSegments(const nav_msgs::msg::Path & path);
154 
164  const geometry_msgs::msg::Pose & start_pose,
165  nav_msgs::msg::Path & path,
166  const nav2_costmap_2d::Costmap2D * costmap,
167  const bool & reversing_segment);
168 
178  const geometry_msgs::msg::Pose & end_pose,
179  nav_msgs::msg::Path & path,
180  const nav2_costmap_2d::Costmap2D * costmap,
181  const bool & reversing_segment);
182 
191  unsigned int findShortestBoundaryExpansionIdx(const BoundaryExpansions & boundary_expansions);
192 
202  const geometry_msgs::msg::Pose & start,
203  const geometry_msgs::msg::Pose & end,
204  BoundaryExpansion & expansion,
205  const nav2_costmap_2d::Costmap2D * costmap);
206 
214  template<typename IteratorT>
215  BoundaryExpansions generateBoundaryExpansionPoints(IteratorT start, IteratorT end);
216 
223  nav_msgs::msg::Path & path,
224  bool & reversing_segment);
225 
226  double min_turning_rad_, tolerance_, data_w_, smooth_w_;
227  int max_its_, refinement_ctr_, refinement_num_;
228  bool is_holonomic_, do_refinement_;
229  MotionModel motion_model_;
230  ompl::base::StateSpacePtr state_space_;
231 };
232 
233 } // namespace nav2_smac_planner
234 
235 #endif // NAV2_SMAC_PLANNER__SMOOTHER_HPP_
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:69
A Conjugate Gradient 2D path smoother implementation.
void initialize(const double &min_turning_radius)
Initialization of the smoother.
Definition: smoother.cpp:44
bool smooth(nav_msgs::msg::Path &path, const nav2_costmap_2d::Costmap2D *costmap, const double &max_time)
Smoother API method.
Definition: smoother.cpp:50
bool smoothImpl(nav_msgs::msg::Path &path, bool &reversing_segment, const nav2_costmap_2d::Costmap2D *costmap, const double &max_time)
Smoother method - does the smoothing on a segment.
Definition: smoother.cpp:105
void updateApproximatePathOrientations(nav_msgs::msg::Path &path, bool &reversing_segment)
For a given path, update the path point orientations based on smoothing.
Definition: smoother.cpp:274
std::vector< PathSegment > findDirectionalPathSegments(const nav_msgs::msg::Path &path)
Finds the starting and end indices of path segments where the robot is traveling in the same directio...
Definition: smoother.cpp:224
void enforceStartBoundaryConditions(const geometry_msgs::msg::Pose &start_pose, nav_msgs::msg::Path &path, const nav2_costmap_2d::Costmap2D *costmap, const bool &reversing_segment)
Enforced minimum curvature boundary conditions on plan output the robot is traveling in the same dire...
Definition: smoother.cpp:429
double getFieldByDim(const geometry_msgs::msg::PoseStamped &msg, const unsigned int &dim)
Get the field value for a given dimension.
Definition: smoother.cpp:199
~Smoother()
A destructor for nav2_smac_planner::Smoother.
Definition: smoother.hpp:90
void enforceEndBoundaryConditions(const geometry_msgs::msg::Pose &end_pose, nav_msgs::msg::Path &path, const nav2_costmap_2d::Costmap2D *costmap, const bool &reversing_segment)
Enforced minimum curvature boundary conditions on plan output the robot is traveling in the same dire...
Definition: smoother.cpp:475
void setFieldByDim(geometry_msgs::msg::PoseStamped &msg, const unsigned int dim, const double &value)
Set the field value for a given dimension.
Definition: smoother.cpp:211
Smoother(const SmootherParams &params)
A constructor for nav2_smac_planner::Smoother.
Definition: smoother.cpp:33
BoundaryExpansions generateBoundaryExpansionPoints(IteratorT start, IteratorT end)
Generates boundary expansions with end idx at least strategic distances away, using either Reverse or...
Definition: smoother.cpp:392
unsigned int findShortestBoundaryExpansionIdx(const BoundaryExpansions &boundary_expansions)
Given a set of boundary expansion, find the one which is shortest such that it is least likely to con...
Definition: smoother.cpp:310
void findBoundaryExpansion(const geometry_msgs::msg::Pose &start, const geometry_msgs::msg::Pose &end, BoundaryExpansion &expansion, const nav2_costmap_2d::Costmap2D *costmap)
Populate a motion model expansion from start->end into expansion.
Definition: smoother.cpp:332
Boundary expansion state.
Definition: smoother.hpp:63
Set of boundary condition points from expansion.
Definition: smoother.hpp:45
BoundaryPoints(double &x_in, double &y_in, double &theta_in)
A constructor for BoundaryPoints.
Definition: smoother.hpp:49
A segment of a path in start/end indices.
Definition: smoother.hpp:35
Parameters for the smoother cost function.