|
| 1 | +// Copyright (c) 2022, 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_SMOOTHER__SIMPLE_SMOOTHER_HPP_ |
| 16 | +#define NAV2_SMOOTHER__SIMPLE_SMOOTHER_HPP_ |
| 17 | + |
| 18 | +#include <cmath> |
| 19 | +#include <vector> |
| 20 | +#include <string> |
| 21 | +#include <iostream> |
| 22 | +#include <memory> |
| 23 | +#include <queue> |
| 24 | +#include <utility> |
| 25 | + |
| 26 | +#include "nav2_core/smoother.hpp" |
| 27 | +#include "nav2_costmap_2d/costmap_2d.hpp" |
| 28 | +#include "nav2_costmap_2d/cost_values.hpp" |
| 29 | +#include "nav2_util/geometry_utils.hpp" |
| 30 | +#include "nav2_util/node_utils.hpp" |
| 31 | +#include "nav_msgs/msg/path.hpp" |
| 32 | +#include "angles/angles.h" |
| 33 | +#include "tf2/utils.h" |
| 34 | + |
| 35 | +namespace nav2_smoother |
| 36 | +{ |
| 37 | + |
| 38 | +/** |
| 39 | + * @class nav2_smoother::PathSegment |
| 40 | + * @brief A segment of a path in start/end indices |
| 41 | + */ |
| 42 | +struct PathSegment |
| 43 | +{ |
| 44 | + unsigned int start; |
| 45 | + unsigned int end; |
| 46 | +}; |
| 47 | + |
| 48 | +typedef std::vector<geometry_msgs::msg::PoseStamped>::iterator PathIterator; |
| 49 | +typedef std::vector<geometry_msgs::msg::PoseStamped>::reverse_iterator ReversePathIterator; |
| 50 | + |
| 51 | +/** |
| 52 | + * @class nav2_smoother::SimpleSmoother |
| 53 | + * @brief A path smoother implementation |
| 54 | + */ |
| 55 | +class SimpleSmoother : public nav2_core::Smoother |
| 56 | +{ |
| 57 | +public: |
| 58 | + /** |
| 59 | + * @brief A constructor for nav2_smoother::SimpleSmoother |
| 60 | + */ |
| 61 | + SimpleSmoother() = default; |
| 62 | + |
| 63 | + /** |
| 64 | + * @brief A destructor for nav2_smoother::SimpleSmoother |
| 65 | + */ |
| 66 | + ~SimpleSmoother() override = default; |
| 67 | + |
| 68 | + void configure( |
| 69 | + const rclcpp_lifecycle::LifecycleNode::WeakPtr &, |
| 70 | + std::string name, const std::shared_ptr<tf2_ros::Buffer> &, |
| 71 | + const std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> &, |
| 72 | + const std::shared_ptr<nav2_costmap_2d::FootprintSubscriber> &) override; |
| 73 | + |
| 74 | + /** |
| 75 | + * @brief Method to cleanup resources. |
| 76 | + */ |
| 77 | + void cleanup() override {costmap_sub_.reset();} |
| 78 | + |
| 79 | + /** |
| 80 | + * @brief Method to activate smoother and any threads involved in execution. |
| 81 | + */ |
| 82 | + void activate() override {} |
| 83 | + |
| 84 | + /** |
| 85 | + * @brief Method to deactivate smoother and any threads involved in execution. |
| 86 | + */ |
| 87 | + void deactivate() override {} |
| 88 | + |
| 89 | + /** |
| 90 | + * @brief Method to smooth given path |
| 91 | + * |
| 92 | + * @param path In-out path to be smoothed |
| 93 | + * @param max_time Maximum duration smoothing should take |
| 94 | + * @return If smoothing was completed (true) or interrupted by time limit (false) |
| 95 | + */ |
| 96 | + bool smooth( |
| 97 | + nav_msgs::msg::Path & path, |
| 98 | + const rclcpp::Duration & max_time) override; |
| 99 | + |
| 100 | +protected: |
| 101 | + /** |
| 102 | + * @brief Smoother method - does the smoothing on a segment |
| 103 | + * @param path Reference to path |
| 104 | + * @param reversing_segment Return if this is a reversing segment |
| 105 | + * @param costmap Pointer to minimal costmap |
| 106 | + * @param max_time Maximum time to compute, stop early if over limit |
| 107 | + * @return If smoothing was successful |
| 108 | + */ |
| 109 | + bool smoothImpl( |
| 110 | + nav_msgs::msg::Path & path, |
| 111 | + bool & reversing_segment, |
| 112 | + const nav2_costmap_2d::Costmap2D * costmap, |
| 113 | + const double & max_time); |
| 114 | + |
| 115 | + /** |
| 116 | + * @brief Get the field value for a given dimension |
| 117 | + * @param msg Current pose to sample |
| 118 | + * @param dim Dimension ID of interest |
| 119 | + * @return dim value |
| 120 | + */ |
| 121 | + inline double getFieldByDim( |
| 122 | + const geometry_msgs::msg::PoseStamped & msg, |
| 123 | + const unsigned int & dim); |
| 124 | + |
| 125 | + /** |
| 126 | + * @brief Set the field value for a given dimension |
| 127 | + * @param msg Current pose to sample |
| 128 | + * @param dim Dimension ID of interest |
| 129 | + * @param value to set the dimention to for the pose |
| 130 | + */ |
| 131 | + inline void setFieldByDim( |
| 132 | + geometry_msgs::msg::PoseStamped & msg, const unsigned int dim, |
| 133 | + const double & value); |
| 134 | + |
| 135 | + /** |
| 136 | + * @brief Finds the starting and end indices of path segments where |
| 137 | + * the robot is traveling in the same direction (e.g. forward vs reverse) |
| 138 | + * @param path Path in which to look for cusps |
| 139 | + * @return Set of index pairs for each segment of the path in a given direction |
| 140 | + */ |
| 141 | + std::vector<PathSegment> findDirectionalPathSegments(const nav_msgs::msg::Path & path); |
| 142 | + |
| 143 | + /** |
| 144 | + * @brief For a given path, update the path point orientations based on smoothing |
| 145 | + * @param path Path to approximate the path orientation in |
| 146 | + * @param reversing_segment Return if this is a reversing segment |
| 147 | + */ |
| 148 | + inline void updateApproximatePathOrientations( |
| 149 | + nav_msgs::msg::Path & path, |
| 150 | + bool & reversing_segment); |
| 151 | + |
| 152 | + double tolerance_, data_w_, smooth_w_; |
| 153 | + int max_its_, refinement_ctr_; |
| 154 | + bool do_refinement_; |
| 155 | + std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub_; |
| 156 | + rclcpp::Logger logger_{rclcpp::get_logger("SimpleSmoother")}; |
| 157 | +}; |
| 158 | + |
| 159 | +} // namespace nav2_smoother |
| 160 | + |
| 161 | +#endif // NAV2_SMOOTHER__SIMPLE_SMOOTHER_HPP_ |
0 commit comments