Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
theta_star_planner.cpp
1 // Copyright 2020 Anshumaan Singh
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.
14 
15 #include <vector>
16 #include <memory>
17 #include <string>
18 #include "nav2_theta_star_planner/theta_star_planner.hpp"
19 #include "nav2_theta_star_planner/theta_star.hpp"
20 
21 namespace nav2_theta_star_planner
22 {
24  const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
25  std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
26  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
27 {
28  planner_ = std::make_unique<theta_star::ThetaStar>();
29  parent_node_ = parent;
30  auto node = parent_node_.lock();
31  logger_ = node->get_logger();
32  clock_ = node->get_clock();
33  name_ = name;
34  tf_ = tf;
35  planner_->costmap_ = costmap_ros->getCostmap();
36  global_frame_ = costmap_ros->getGlobalFrameID();
37 
38  nav2_util::declare_parameter_if_not_declared(
39  node, name_ + ".how_many_corners", rclcpp::ParameterValue(8));
40 
41  node->get_parameter(name_ + ".how_many_corners", planner_->how_many_corners_);
42 
43  if (planner_->how_many_corners_ != 8 && planner_->how_many_corners_ != 4) {
44  planner_->how_many_corners_ = 8;
45  RCLCPP_WARN(logger_, "Your value for - .how_many_corners was overridden, and is now set to 8");
46  }
47 
48  nav2_util::declare_parameter_if_not_declared(
49  node, name_ + ".allow_unknown", rclcpp::ParameterValue(true));
50  node->get_parameter(name_ + ".allow_unknown", planner_->allow_unknown_);
51 
52  nav2_util::declare_parameter_if_not_declared(
53  node, name_ + ".w_euc_cost", rclcpp::ParameterValue(1.0));
54  node->get_parameter(name_ + ".w_euc_cost", planner_->w_euc_cost_);
55 
56  nav2_util::declare_parameter_if_not_declared(
57  node, name_ + ".w_traversal_cost", rclcpp::ParameterValue(2.0));
58  node->get_parameter(name_ + ".w_traversal_cost", planner_->w_traversal_cost_);
59 
60  planner_->w_heuristic_cost_ = planner_->w_euc_cost_ < 1.0 ? planner_->w_euc_cost_ : 1.0;
61 
62  nav2_util::declare_parameter_if_not_declared(
63  node, name_ + ".terminal_checking_interval", rclcpp::ParameterValue(5000));
64  node->get_parameter(name_ + ".terminal_checking_interval", planner_->terminal_checking_interval_);
65 
66  nav2_util::declare_parameter_if_not_declared(
67  node, name + ".use_final_approach_orientation", rclcpp::ParameterValue(false));
68  node->get_parameter(name + ".use_final_approach_orientation", use_final_approach_orientation_);
69 }
70 
72 {
73  RCLCPP_INFO(logger_, "CleaningUp plugin %s of type nav2_theta_star_planner", name_.c_str());
74  planner_.reset();
75 }
76 
78 {
79  RCLCPP_INFO(logger_, "Activating plugin %s of type nav2_theta_star_planner", name_.c_str());
80  // Add callback for dynamic parameters
81  auto node = parent_node_.lock();
82  dyn_params_handler_ = node->add_on_set_parameters_callback(
83  std::bind(&ThetaStarPlanner::dynamicParametersCallback, this, std::placeholders::_1));
84 }
85 
87 {
88  RCLCPP_INFO(logger_, "Deactivating plugin %s of type nav2_theta_star_planner", name_.c_str());
89  auto node = parent_node_.lock();
90  if (node && dyn_params_handler_) {
91  node->remove_on_set_parameters_callback(dyn_params_handler_.get());
92  }
93  dyn_params_handler_.reset();
94 }
95 
96 nav_msgs::msg::Path ThetaStarPlanner::createPlan(
97  const geometry_msgs::msg::PoseStamped & start,
98  const geometry_msgs::msg::PoseStamped & goal,
99  std::function<bool()> cancel_checker)
100 {
101  nav_msgs::msg::Path global_path;
102  auto start_time = std::chrono::steady_clock::now();
103 
104  std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(planner_->costmap_->getMutex()));
105 
106  // Corner case of start and goal beeing on the same cell
107  unsigned int mx_start, my_start, mx_goal, my_goal;
108  if (!planner_->costmap_->worldToMap(
109  start.pose.position.x, start.pose.position.y, mx_start, my_start))
110  {
112  "Start Coordinates of(" + std::to_string(start.pose.position.x) + ", " +
113  std::to_string(start.pose.position.y) + ") was outside bounds");
114  }
115 
116  if (!planner_->costmap_->worldToMap(
117  goal.pose.position.x, goal.pose.position.y, mx_goal, my_goal))
118  {
120  "Goal Coordinates of(" + std::to_string(goal.pose.position.x) + ", " +
121  std::to_string(goal.pose.position.y) + ") was outside bounds");
122  }
123 
124  if (planner_->costmap_->getCost(mx_goal, my_goal) == nav2_costmap_2d::LETHAL_OBSTACLE) {
126  "Goal Coordinates of(" + std::to_string(goal.pose.position.x) + ", " +
127  std::to_string(goal.pose.position.y) + ") was in lethal cost");
128  }
129 
130  if (mx_start == mx_goal && my_start == my_goal) {
131  global_path.header.stamp = clock_->now();
132  global_path.header.frame_id = global_frame_;
133  geometry_msgs::msg::PoseStamped pose;
134  pose.header = global_path.header;
135  pose.pose.position.z = 0.0;
136 
137  pose.pose = start.pose;
138  // if we have a different start and goal orientation, set the unique path pose to the goal
139  // orientation, unless use_final_approach_orientation=true where we need it to be the start
140  // orientation to avoid movement from the local planner
141  if (start.pose.orientation != goal.pose.orientation && !use_final_approach_orientation_) {
142  pose.pose.orientation = goal.pose.orientation;
143  }
144  global_path.poses.push_back(pose);
145  return global_path;
146  }
147 
148  planner_->clearStart();
149  planner_->setStartAndGoal(start, goal);
150  RCLCPP_DEBUG(
151  logger_, "Got the src and dst... (%i, %i) && (%i, %i)",
152  planner_->src_.x, planner_->src_.y, planner_->dst_.x, planner_->dst_.y);
153  getPlan(global_path, cancel_checker);
154  // check if a plan is generated
155  size_t plan_size = global_path.poses.size();
156  if (plan_size > 0) {
157  global_path.poses.back().pose.orientation = goal.pose.orientation;
158  }
159 
160  // If use_final_approach_orientation=true, interpolate the last pose orientation from the
161  // previous pose to set the orientation to the 'final approach' orientation of the robot so
162  // it does not rotate.
163  // And deal with corner case of plan of length 1
164  if (use_final_approach_orientation_) {
165  if (plan_size == 1) {
166  global_path.poses.back().pose.orientation = start.pose.orientation;
167  } else if (plan_size > 1) {
168  double dx, dy, theta;
169  auto last_pose = global_path.poses.back().pose.position;
170  auto approach_pose = global_path.poses[plan_size - 2].pose.position;
171  dx = last_pose.x - approach_pose.x;
172  dy = last_pose.y - approach_pose.y;
173  theta = atan2(dy, dx);
174  global_path.poses.back().pose.orientation =
175  nav2_util::geometry_utils::orientationAroundZAxis(theta);
176  }
177  }
178 
179  auto stop_time = std::chrono::steady_clock::now();
180  auto dur = std::chrono::duration_cast<std::chrono::microseconds>(stop_time - start_time);
181  RCLCPP_DEBUG(logger_, "the time taken is : %i", static_cast<int>(dur.count()));
182  RCLCPP_DEBUG(logger_, "the nodes_opened are: %i", planner_->nodes_opened);
183  return global_path;
184 }
185 
187  nav_msgs::msg::Path & global_path,
188  std::function<bool()> cancel_checker)
189 {
190  std::vector<coordsW> path;
191  if (planner_->isUnsafeToPlan()) {
192  global_path.poses.clear();
193  throw nav2_core::PlannerException("Either of the start or goal pose are an obstacle! ");
194  } else if (planner_->generatePath(path, cancel_checker)) {
195  global_path = linearInterpolation(path, planner_->costmap_->getResolution());
196  } else {
197  global_path.poses.clear();
198  throw nav2_core::NoValidPathCouldBeFound("Could not generate path between the given poses");
199  }
200  global_path.header.stamp = clock_->now();
201  global_path.header.frame_id = global_frame_;
202 }
203 
205  const std::vector<coordsW> & raw_path,
206  const double & dist_bw_points)
207 {
208  nav_msgs::msg::Path pa;
209 
210  geometry_msgs::msg::PoseStamped p1;
211  for (unsigned int j = 0; j < raw_path.size() - 1; j++) {
212  coordsW pt1 = raw_path[j];
213  p1.pose.position.x = pt1.x;
214  p1.pose.position.y = pt1.y;
215  pa.poses.push_back(p1);
216 
217  coordsW pt2 = raw_path[j + 1];
218  double distance = std::hypot(pt2.x - pt1.x, pt2.y - pt1.y);
219  int loops = static_cast<int>(distance / dist_bw_points);
220  double sin_alpha = (pt2.y - pt1.y) / distance;
221  double cos_alpha = (pt2.x - pt1.x) / distance;
222  for (int k = 1; k < loops; k++) {
223  p1.pose.position.x = pt1.x + k * dist_bw_points * cos_alpha;
224  p1.pose.position.y = pt1.y + k * dist_bw_points * sin_alpha;
225  pa.poses.push_back(p1);
226  }
227  }
228 
229  return pa;
230 }
231 
232 rcl_interfaces::msg::SetParametersResult
233 ThetaStarPlanner::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
234 {
235  rcl_interfaces::msg::SetParametersResult result;
236  for (auto parameter : parameters) {
237  const auto & type = parameter.get_type();
238  const auto & name = parameter.get_name();
239 
240  if (type == ParameterType::PARAMETER_INTEGER) {
241  if (name == name_ + ".how_many_corners") {
242  planner_->how_many_corners_ = parameter.as_int();
243  }
244  if (name == name_ + ".terminal_checking_interval") {
245  planner_->terminal_checking_interval_ = parameter.as_int();
246  }
247  } else if (type == ParameterType::PARAMETER_DOUBLE) {
248  if (name == name_ + ".w_euc_cost") {
249  planner_->w_euc_cost_ = parameter.as_double();
250  } else if (name == name_ + ".w_traversal_cost") {
251  planner_->w_traversal_cost_ = parameter.as_double();
252  }
253  } else if (type == ParameterType::PARAMETER_BOOL) {
254  if (name == name_ + ".use_final_approach_orientation") {
255  use_final_approach_orientation_ = parameter.as_bool();
256  } else if (name == name_ + ".allow_unknown") {
257  planner_->allow_unknown_ = parameter.as_bool();
258  }
259  }
260  }
261 
262  result.successful = true;
263  return result;
264 }
265 
266 } // namespace nav2_theta_star_planner
267 
268 #include "pluginlib/class_list_macros.hpp"
Abstract interface for global planners to adhere to with pluginlib.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a paramter change is detected.
void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, std::string name, std::shared_ptr< tf2_ros::Buffer > tf, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros) override
void getPlan(nav_msgs::msg::Path &global_path, std::function< bool()> cancel_checker)
the function responsible for calling the algorithm and retrieving a path from it
void cleanup() override
Method to cleanup resources used on shutdown.
nav_msgs::msg::Path createPlan(const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal, std::function< bool()> cancel_checker) override
Creating a plan from start and goal poses.
static nav_msgs::msg::Path linearInterpolation(const std::vector< coordsW > &raw_path, const double &dist_bw_points)
interpolates points between the consecutive waypoints of the path
void deactivate() override
Method to deactive planner and any threads involved in execution.
void activate() override
Method to active planner and any threads involved in execution.