Nav2 Navigation Stack - jazzy  jazzy
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 "nav2_constrained_smoother/constrained_smoother.hpp"
24 #include "nav2_util/node_utils.hpp"
25 #include "nav2_util/geometry_utils.hpp"
26 #include "nav2_core/smoother_exceptions.hpp"
27 
28 #include "pluginlib/class_loader.hpp"
29 #include "pluginlib/class_list_macros.hpp"
30 
31 #include "tf2/utils.h"
32 
33 using nav2_util::declare_parameter_if_not_declared;
34 using nav2_util::geometry_utils::euclidean_distance;
35 using namespace nav2_costmap_2d; // NOLINT
36 
37 namespace nav2_constrained_smoother
38 {
39 
40 void ConstrainedSmoother::configure(
41  const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
42  std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
43  std::shared_ptr<nav2_costmap_2d::CostmapSubscriber> costmap_sub,
44  std::shared_ptr<nav2_costmap_2d::FootprintSubscriber>)
45 {
46  auto node = parent.lock();
47  if (!node) {
48  throw std::runtime_error("Unable to lock node!");
49  }
50 
51  costmap_sub_ = costmap_sub;
52  tf_ = tf;
53  plugin_name_ = name;
54  logger_ = node->get_logger();
55 
56  smoother_ = std::make_unique<nav2_constrained_smoother::Smoother>();
57  optimizer_params_.get(node.get(), name);
58  smoother_params_.get(node.get(), name);
59  smoother_->initialize(optimizer_params_);
60 }
61 
62 void ConstrainedSmoother::cleanup()
63 {
64  RCLCPP_INFO(
65  logger_,
66  "Cleaning up smoother: %s of type"
67  " nav2_constrained_smoother::ConstrainedSmoother",
68  plugin_name_.c_str());
69 }
70 
71 void ConstrainedSmoother::activate()
72 {
73  RCLCPP_INFO(
74  logger_,
75  "Activating smoother: %s of type "
76  "nav2_constrained_smoother::ConstrainedSmoother",
77  plugin_name_.c_str());
78 }
79 
80 void ConstrainedSmoother::deactivate()
81 {
82  RCLCPP_INFO(
83  logger_,
84  "Deactivating smoother: %s of type "
85  "nav2_constrained_smoother::ConstrainedSmoother",
86  plugin_name_.c_str());
87 }
88 
89 bool ConstrainedSmoother::smooth(nav_msgs::msg::Path & path, const rclcpp::Duration & max_time)
90 {
91  if (path.poses.size() < 2) {
92  return true;
93  }
94 
95  // populate smoother input with (x, y, forward/reverse dir)
96  std::vector<Eigen::Vector3d> path_world;
97  path_world.reserve(path.poses.size());
98  // smoother keeps record of start/end orientations so that it
99  // can use them in the final path, preventing degradation of these (often important) values
100  Eigen::Vector2d start_dir;
101  Eigen::Vector2d end_dir;
102  for (size_t i = 0; i < path.poses.size(); i++) {
103  auto & pose = path.poses[i].pose;
104  double angle = tf2::getYaw(pose.orientation);
105  Eigen::Vector2d orientation(cos(angle), sin(angle));
106  if (i == path.poses.size() - 1) {
107  // Note: `reversing` indicates the direction of the segment after the point and
108  // there is no segment after the last point. Most probably the value is irrelevant, but
109  // copying it from the last but one point, just to make it defined...
110  path_world.emplace_back(pose.position.x, pose.position.y, path_world.back()[2]);
111  end_dir = orientation;
112  } else {
113  auto & pos_next = path.poses[i + 1].pose.position;
114  Eigen::Vector2d mvmt(pos_next.x - pose.position.x, pos_next.y - pose.position.y);
115  // robot is considered reversing when angle between its orientation and movement direction
116  // is more than 90 degrees (i.e. dot product is less than 0)
117  bool reversing = smoother_params_.reversing_enabled && orientation.dot(mvmt) < 0;
118  // we transform boolean value of "reversing" into sign of movement direction (+1 or -1)
119  // to simplify further computations
120  path_world.emplace_back(pose.position.x, pose.position.y, reversing ? -1 : 1);
121  if (i == 0) {
122  start_dir = orientation;
123  } else if (i == 1 && !smoother_params_.keep_start_orientation) {
124  // overwrite start forward/reverse when orientation was set to be ignored
125  // note: start_dir is overwritten inside Smoother::upsampleAndPopulate() method
126  path_world[0][2] = path_world.back()[2];
127  }
128  }
129  }
130 
131  smoother_params_.max_time = max_time.seconds();
132 
133  // Smooth plan
134  auto costmap = costmap_sub_->getCostmap();
135  std::lock_guard<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getMutex()));
136  if (!smoother_->smooth(path_world, start_dir, end_dir, costmap.get(), smoother_params_)) {
137  RCLCPP_WARN(
138  logger_,
139  "%s: failed to smooth plan, Ceres could not find a usable solution to optimize.",
140  plugin_name_.c_str());
142  "Failed to smooth plan, Ceres could not find a usable solution");
143  }
144 
145  // populate final path
146  geometry_msgs::msg::PoseStamped pose;
147  pose.header = path.poses.front().header;
148  path.poses.clear();
149  path.poses.reserve(path_world.size());
150  for (auto & pw : path_world) {
151  pose.pose.position.x = pw[0];
152  pose.pose.position.y = pw[1];
153  pose.pose.orientation.z = sin(pw[2] / 2);
154  pose.pose.orientation.w = cos(pw[2] / 2);
155 
156  path.poses.push_back(pose);
157  }
158 
159  return true;
160 }
161 
162 } // namespace nav2_constrained_smoother
163 
164 // Register this smoother as a nav2_core plugin
165 PLUGINLIB_EXPORT_CLASS(
Regulated pure pursuit controller plugin.
smoother interface that acts as a virtual base class for all smoother plugins
Definition: smoother.hpp:39