Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
constrained_smoother.cpp
1 // Copyright (c) 2021 RoboTech Vision
2 // Copyright (c) 2020 Shrijit Singh
3 // Copyright (c) 2020 Samsung Research America
4 //
5 // Licensed under the Apache License, Version 2.0 (the "License");
6 // you may not use this file except in compliance with the License.
7 // You may obtain a copy of the License at
8 //
9 // http://www.apache.org/licenses/LICENSE-2.0
10 //
11 // Unless required by applicable law or agreed to in writing, software
12 // distributed under the License is distributed on an "AS IS" BASIS,
13 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 // See the License for the specific language governing permissions and
15 // limitations under the License.
16 
17 #include <algorithm>
18 #include <string>
19 #include <memory>
20 #include <utility>
21 #include <vector>
22 
23 #include "geometry_msgs/msg/pose_stamped.hpp"
24 
25 #include "nav2_constrained_smoother/constrained_smoother.hpp"
26 #include "nav2_ros_common/node_utils.hpp"
27 #include "nav2_util/geometry_utils.hpp"
28 #include "nav2_core/smoother_exceptions.hpp"
29 
30 #include "pluginlib/class_loader.hpp"
31 #include "pluginlib/class_list_macros.hpp"
32 
33 #include "tf2/utils.hpp"
34 
35 using nav2_util::geometry_utils::euclidean_distance;
36 using namespace nav2_costmap_2d; // NOLINT
37 
38 namespace nav2_constrained_smoother
39 {
40 
41 void ConstrainedSmoother::configure(
42  const nav2::LifecycleNode::WeakPtr & parent,
43  std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
44  std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub,
45  std::shared_ptr<nav2_costmap_2d::FootprintSubscriber>)
46 {
47  auto node = parent.lock();
48  if (!node) {
49  throw std::runtime_error("Unable to lock node!");
50  }
51 
52  costmap_sub_ = costmap_sub;
53  tf_ = tf;
54  plugin_name_ = name;
55  logger_ = node->get_logger();
56 
57  smoother_ = std::make_unique<nav2_constrained_smoother::Smoother>();
58  optimizer_params_.get(node.get(), name);
59  smoother_params_.get(node.get(), name);
60  smoother_->initialize(optimizer_params_);
61 }
62 
63 void ConstrainedSmoother::cleanup()
64 {
65  RCLCPP_INFO(
66  logger_,
67  "Cleaning up smoother: %s of type"
68  " nav2_constrained_smoother::ConstrainedSmoother",
69  plugin_name_.c_str());
70 }
71 
72 void ConstrainedSmoother::activate()
73 {
74  RCLCPP_INFO(
75  logger_,
76  "Activating smoother: %s of type "
77  "nav2_constrained_smoother::ConstrainedSmoother",
78  plugin_name_.c_str());
79 }
80 
81 void ConstrainedSmoother::deactivate()
82 {
83  RCLCPP_INFO(
84  logger_,
85  "Deactivating smoother: %s of type "
86  "nav2_constrained_smoother::ConstrainedSmoother",
87  plugin_name_.c_str());
88 }
89 
90 bool ConstrainedSmoother::smooth(nav_msgs::msg::Path & path, const rclcpp::Duration & max_time)
91 {
92  if (path.poses.size() < 2) {
93  return true;
94  }
95 
96  // populate smoother input with (x, y, forward/reverse dir)
97  std::vector<Eigen::Vector3d> path_world;
98  path_world.reserve(path.poses.size());
99  // smoother keeps record of start/end orientations so that it
100  // can use them in the final path, preventing degradation of these (often important) values
101  Eigen::Vector2d start_dir;
102  Eigen::Vector2d end_dir;
103  for (size_t i = 0; i < path.poses.size(); i++) {
104  auto & pose = path.poses[i].pose;
105  double angle = tf2::getYaw(pose.orientation);
106  Eigen::Vector2d orientation(cos(angle), sin(angle));
107  if (i == path.poses.size() - 1) {
108  // Note: `reversing` indicates the direction of the segment after the point and
109  // there is no segment after the last point. Most probably the value is irrelevant, but
110  // copying it from the last but one point, just to make it defined...
111  path_world.emplace_back(pose.position.x, pose.position.y, path_world.back()[2]);
112  end_dir = orientation;
113  } else {
114  auto & pos_next = path.poses[i + 1].pose.position;
115  Eigen::Vector2d mvmt(pos_next.x - pose.position.x, pos_next.y - pose.position.y);
116  // robot is considered reversing when angle between its orientation and movement direction
117  // is more than 90 degrees (i.e. dot product is less than 0)
118  bool reversing = smoother_params_.reversing_enabled && orientation.dot(mvmt) < 0;
119  // we transform boolean value of "reversing" into sign of movement direction (+1 or -1)
120  // to simplify further computations
121  path_world.emplace_back(pose.position.x, pose.position.y, reversing ? -1 : 1);
122  if (i == 0) {
123  start_dir = orientation;
124  } else if (i == 1 && !smoother_params_.keep_start_orientation) {
125  // overwrite start forward/reverse when orientation was set to be ignored
126  // note: start_dir is overwritten inside Smoother::upsampleAndPopulate() method
127  path_world[0][2] = path_world.back()[2];
128  }
129  }
130  }
131 
132  smoother_params_.max_time = max_time.seconds();
133 
134  // Smooth plan
135  auto costmap = costmap_sub_->getCostmap();
136  std::lock_guard<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getMutex()));
137  if (!smoother_->smooth(path_world, start_dir, end_dir, costmap.get(), smoother_params_)) {
138  RCLCPP_WARN(
139  logger_,
140  "%s: failed to smooth plan, Ceres could not find a usable solution to optimize.",
141  plugin_name_.c_str());
143  "Failed to smooth plan, Ceres could not find a usable solution");
144  }
145 
146  // populate final path
147  geometry_msgs::msg::PoseStamped pose;
148  pose.header = path.poses.front().header;
149  path.poses.clear();
150  path.poses.reserve(path_world.size());
151  for (auto & pw : path_world) {
152  pose.pose.position.x = pw[0];
153  pose.pose.position.y = pw[1];
154  pose.pose.orientation.z = sin(pw[2] / 2);
155  pose.pose.orientation.w = cos(pw[2] / 2);
156 
157  path.poses.push_back(pose);
158  }
159 
160  return true;
161 }
162 
163 } // namespace nav2_constrained_smoother
164 
165 // Register this smoother as a nav2_core plugin
166 PLUGINLIB_EXPORT_CLASS(
Regulated pure pursuit controller plugin.
smoother interface that acts as a virtual base class for all smoother plugins
Definition: smoother.hpp:38