Nav2 Navigation Stack - jazzy  jazzy
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 <cmath>
19 #include <vector>
20 #include <iostream>
21 #include <memory>
22 #include <queue>
23 #include <utility>
24 
25 #include "nav2_costmap_2d/costmap_2d.hpp"
26 #include "nav2_smac_planner/types.hpp"
27 #include "nav2_smac_planner/constants.hpp"
28 #include "nav2_util/geometry_utils.hpp"
29 #include "nav_msgs/msg/path.hpp"
30 #include "angles/angles.h"
31 #include "tf2/utils.h"
32 #include "ompl/base/StateSpace.h"
33 #include "ompl/base/spaces/DubinsStateSpace.h"
34 
35 namespace nav2_smac_planner
36 {
37 
43 {
44  unsigned int start;
45  unsigned int end;
46 };
47 
53 {
57  BoundaryPoints(double & x_in, double & y_in, double & theta_in)
58  : x(x_in), y(y_in), theta(theta_in)
59  {}
60 
61  double x;
62  double y;
63  double theta;
64 };
65 
71 {
72  double path_end_idx{0.0};
73  double expansion_path_length{0.0};
74  double original_path_length{0.0};
75  std::vector<BoundaryPoints> pts;
76  bool in_collision{false};
77 };
78 
79 typedef std::vector<BoundaryExpansion> BoundaryExpansions;
80 typedef std::vector<geometry_msgs::msg::PoseStamped>::iterator PathIterator;
81 typedef std::vector<geometry_msgs::msg::PoseStamped>::reverse_iterator ReversePathIterator;
82 
87 class Smoother
88 {
89 public:
93  explicit Smoother(const SmootherParams & params);
94 
98  ~Smoother() {}
99 
105  void initialize(
106  const double & min_turning_radius);
107 
115  bool smooth(
116  nav_msgs::msg::Path & path,
117  const nav2_costmap_2d::Costmap2D * costmap,
118  const double & max_time);
119 
120 protected:
129  bool smoothImpl(
130  nav_msgs::msg::Path & path,
131  bool & reversing_segment,
132  const nav2_costmap_2d::Costmap2D * costmap,
133  const double & max_time);
134 
141  inline double getFieldByDim(
142  const geometry_msgs::msg::PoseStamped & msg,
143  const unsigned int & dim);
144 
151  inline void setFieldByDim(
152  geometry_msgs::msg::PoseStamped & msg, const unsigned int dim,
153  const double & value);
154 
161  std::vector<PathSegment> findDirectionalPathSegments(const nav_msgs::msg::Path & path);
162 
172  const geometry_msgs::msg::Pose & start_pose,
173  nav_msgs::msg::Path & path,
174  const nav2_costmap_2d::Costmap2D * costmap,
175  const bool & reversing_segment);
176 
186  const geometry_msgs::msg::Pose & end_pose,
187  nav_msgs::msg::Path & path,
188  const nav2_costmap_2d::Costmap2D * costmap,
189  const bool & reversing_segment);
190 
199  unsigned int findShortestBoundaryExpansionIdx(const BoundaryExpansions & boundary_expansions);
200 
210  const geometry_msgs::msg::Pose & start,
211  const geometry_msgs::msg::Pose & end,
212  BoundaryExpansion & expansion,
213  const nav2_costmap_2d::Costmap2D * costmap);
214 
222  template<typename IteratorT>
223  BoundaryExpansions generateBoundaryExpansionPoints(IteratorT start, IteratorT end);
224 
231  nav_msgs::msg::Path & path,
232  bool & reversing_segment);
233 
234  double min_turning_rad_, tolerance_, data_w_, smooth_w_;
235  int max_its_, refinement_ctr_, refinement_num_;
236  bool is_holonomic_, do_refinement_;
237  MotionModel motion_model_;
238  ompl::base::StateSpacePtr state_space_;
239 };
240 
241 } // namespace nav2_smac_planner
242 
243 #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:68
A Conjugate Gradient 2D path smoother implementation.
void initialize(const double &min_turning_radius)
Initialization of the smoother.
Definition: smoother.cpp:37
bool smooth(nav_msgs::msg::Path &path, const nav2_costmap_2d::Costmap2D *costmap, const double &max_time)
Smoother API method.
Definition: smoother.cpp:43
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:98
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:267
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:217
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:422
double getFieldByDim(const geometry_msgs::msg::PoseStamped &msg, const unsigned int &dim)
Get the field value for a given dimension.
Definition: smoother.cpp:192
~Smoother()
A destructor for nav2_smac_planner::Smoother.
Definition: smoother.hpp:98
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:468
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:204
Smoother(const SmootherParams &params)
A constructor for nav2_smac_planner::Smoother.
Definition: smoother.cpp:26
BoundaryExpansions generateBoundaryExpansionPoints(IteratorT start, IteratorT end)
Generates boundary expansions with end idx at least strategic distances away, using either Reverse or...
Definition: smoother.cpp:385
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:303
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:325
Boundary expansion state.
Definition: smoother.hpp:71
Set of boundary condition points from expansion.
Definition: smoother.hpp:53
BoundaryPoints(double &x_in, double &y_in, double &theta_in)
A constructor for BoundaryPoints.
Definition: smoother.hpp:57
A segment of a path in start/end indices.
Definition: smoother.hpp:43
Parameters for the smoother cost function.