15 #ifndef NAV2_SMAC_PLANNER__SMOOTHER_HPP_
16 #define NAV2_SMAC_PLANNER__SMOOTHER_HPP_
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"
27 namespace nav2_smac_planner
50 : x(x_in), y(y_in), theta(theta_in)
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};
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;
98 const double & min_turning_radius);
108 nav_msgs::msg::Path & path,
110 const double & max_time);
122 nav_msgs::msg::Path & path,
123 bool & reversing_segment,
125 const double & max_time);
134 const geometry_msgs::msg::PoseStamped & msg,
135 const unsigned int & dim);
144 geometry_msgs::msg::PoseStamped & msg,
const unsigned int dim,
145 const double & value);
164 const geometry_msgs::msg::Pose & start_pose,
165 nav_msgs::msg::Path & path,
167 const bool & reversing_segment);
178 const geometry_msgs::msg::Pose & end_pose,
179 nav_msgs::msg::Path & path,
181 const bool & reversing_segment);
202 const geometry_msgs::msg::Pose & start,
203 const geometry_msgs::msg::Pose & end,
214 template<
typename IteratorT>
223 nav_msgs::msg::Path & path,
224 bool & reversing_segment);
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_;
A 2D costmap provides a mapping between points in the world and their associated "costs".
A Conjugate Gradient 2D path smoother implementation.
void initialize(const double &min_turning_radius)
Initialization of the smoother.
bool smooth(nav_msgs::msg::Path &path, const nav2_costmap_2d::Costmap2D *costmap, const double &max_time)
Smoother API method.
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.
void updateApproximatePathOrientations(nav_msgs::msg::Path &path, bool &reversing_segment)
For a given path, update the path point orientations based on smoothing.
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...
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...
double getFieldByDim(const geometry_msgs::msg::PoseStamped &msg, const unsigned int &dim)
Get the field value for a given dimension.
~Smoother()
A destructor for nav2_smac_planner::Smoother.
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...
void setFieldByDim(geometry_msgs::msg::PoseStamped &msg, const unsigned int dim, const double &value)
Set the field value for a given dimension.
Smoother(const SmootherParams ¶ms)
A constructor for nav2_smac_planner::Smoother.
BoundaryExpansions generateBoundaryExpansionPoints(IteratorT start, IteratorT end)
Generates boundary expansions with end idx at least strategic distances away, using either Reverse or...
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...
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.
Boundary expansion state.
Set of boundary condition points from expansion.
BoundaryPoints(double &x_in, double &y_in, double &theta_in)
A constructor for BoundaryPoints.
A segment of a path in start/end indices.
Parameters for the smoother cost function.