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
40 : x(x_in), y(y_in), theta(theta_in)
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};
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;
88 const double & min_turning_radius);
98 nav_msgs::msg::Path & path,
100 const double & max_time);
112 nav_msgs::msg::Path & path,
113 bool & reversing_segment,
115 const double & max_time);
124 const geometry_msgs::msg::PoseStamped & msg,
125 const unsigned int & dim);
134 geometry_msgs::msg::PoseStamped & msg,
const unsigned int dim,
135 const double & value);
146 const geometry_msgs::msg::Pose & start_pose,
147 nav_msgs::msg::Path & path,
149 const bool & reversing_segment);
160 const geometry_msgs::msg::Pose & end_pose,
161 nav_msgs::msg::Path & path,
163 const bool & reversing_segment);
184 const geometry_msgs::msg::Pose & start,
185 const geometry_msgs::msg::Pose & end,
196 template<
typename IteratorT>
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_;
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 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.
Parameters for the smoother cost function.