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