Nav2 Navigation Stack - rolling  main
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 {
39  BoundaryPoints(double & x_in, double & y_in, double & theta_in)
40  : x(x_in), y(y_in), theta(theta_in)
41  {}
42 
43  double x;
44  double y;
45  double theta;
46 };
47 
53 {
54  double path_end_idx{0.0};
55  double expansion_path_length{0.0};
56  double original_path_length{0.0};
57  std::vector<BoundaryPoints> pts;
58  bool in_collision{false};
59 };
60 
61 typedef std::vector<BoundaryExpansion> BoundaryExpansions;
62 typedef std::vector<geometry_msgs::msg::PoseStamped>::iterator PathIterator;
63 typedef std::vector<geometry_msgs::msg::PoseStamped>::reverse_iterator ReversePathIterator;
64 
69 class Smoother
70 {
71 public:
75  explicit Smoother(const SmootherParams & params);
76 
80  ~Smoother() {}
81 
87  void initialize(
88  const double & min_turning_radius);
89 
97  bool smooth(
98  nav_msgs::msg::Path & path,
99  const nav2_costmap_2d::Costmap2D * costmap,
100  const double & max_time);
101 
102 protected:
111  bool smoothImpl(
112  nav_msgs::msg::Path & path,
113  bool & reversing_segment,
114  const nav2_costmap_2d::Costmap2D * costmap,
115  const double & max_time);
116 
123  inline double getFieldByDim(
124  const geometry_msgs::msg::PoseStamped & msg,
125  const unsigned int & dim);
126 
133  inline void setFieldByDim(
134  geometry_msgs::msg::PoseStamped & msg, const unsigned int dim,
135  const double & value);
136 
146  const geometry_msgs::msg::Pose & start_pose,
147  nav_msgs::msg::Path & path,
148  const nav2_costmap_2d::Costmap2D * costmap,
149  const bool & reversing_segment);
150 
160  const geometry_msgs::msg::Pose & end_pose,
161  nav_msgs::msg::Path & path,
162  const nav2_costmap_2d::Costmap2D * costmap,
163  const bool & reversing_segment);
164 
173  unsigned int findShortestBoundaryExpansionIdx(const BoundaryExpansions & boundary_expansions);
174 
184  const geometry_msgs::msg::Pose & start,
185  const geometry_msgs::msg::Pose & end,
186  BoundaryExpansion & expansion,
187  const nav2_costmap_2d::Costmap2D * costmap);
188 
196  template<typename IteratorT>
197  BoundaryExpansions generateBoundaryExpansionPoints(IteratorT start, IteratorT end);
198 
199  double min_turning_rad_, tolerance_, data_w_, smooth_w_;
200  int max_its_, refinement_ctr_, refinement_num_;
201  bool is_holonomic_, do_refinement_;
202  MotionModel motion_model_;
203  ompl::base::StateSpacePtr state_space_;
204 };
205 
206 } // namespace nav2_smac_planner
207 
208 #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:46
bool smooth(nav_msgs::msg::Path &path, const nav2_costmap_2d::Costmap2D *costmap, const double &max_time)
Smoother API method.
Definition: smoother.cpp:52
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:108
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:346
double getFieldByDim(const geometry_msgs::msg::PoseStamped &msg, const unsigned int &dim)
Get the field value for a given dimension.
Definition: smoother.cpp:202
~Smoother()
A destructor for nav2_smac_planner::Smoother.
Definition: smoother.hpp:80
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:392
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:214
Smoother(const SmootherParams &params)
A constructor for nav2_smac_planner::Smoother.
Definition: smoother.cpp:35
BoundaryExpansions generateBoundaryExpansionPoints(IteratorT start, IteratorT end)
Generates boundary expansions with end idx at least strategic distances away, using either Reverse or...
Definition: smoother.cpp:309
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:227
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:249
Boundary expansion state.
Definition: smoother.hpp:53
Set of boundary condition points from expansion.
Definition: smoother.hpp:35
BoundaryPoints(double &x_in, double &y_in, double &theta_in)
A constructor for BoundaryPoints.
Definition: smoother.hpp:39
Parameters for the smoother cost function.