Nav2 Navigation Stack - humble  humble
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 + ".use_final_approach_orientation", rclcpp::ParameterValue(false));
64  node->get_parameter(name + ".use_final_approach_orientation", use_final_approach_orientation_);
65 }
66 
68 {
69  RCLCPP_INFO(logger_, "CleaningUp plugin %s of type nav2_theta_star_planner", name_.c_str());
70  planner_.reset();
71 }
72 
74 {
75  RCLCPP_INFO(logger_, "Activating plugin %s of type nav2_theta_star_planner", name_.c_str());
76  // Add callback for dynamic parameters
77  auto node = parent_node_.lock();
78  dyn_params_handler_ = node->add_on_set_parameters_callback(
79  std::bind(&ThetaStarPlanner::dynamicParametersCallback, this, std::placeholders::_1));
80 }
81 
83 {
84  RCLCPP_INFO(logger_, "Deactivating plugin %s of type nav2_theta_star_planner", name_.c_str());
85 }
86 
87 nav_msgs::msg::Path ThetaStarPlanner::createPlan(
88  const geometry_msgs::msg::PoseStamped & start,
89  const geometry_msgs::msg::PoseStamped & goal)
90 {
91  nav_msgs::msg::Path global_path;
92  auto start_time = std::chrono::steady_clock::now();
93 
94  std::unique_lock<nav2_costmap_2d::Costmap2D::mutex_t> lock(*(planner_->costmap_->getMutex()));
95 
96  // Corner case of start and goal beeing on the same cell
97  unsigned int mx_start, my_start, mx_goal, my_goal;
98  if (!planner_->costmap_->worldToMap(
99  start.pose.position.x, start.pose.position.y, mx_start, my_start))
100  {
101  RCLCPP_WARN(logger_, "Start Coordinates were outside map bounds");
102  return global_path;
103  }
104 
105  if (!planner_->costmap_->worldToMap(
106  goal.pose.position.x, goal.pose.position.y, mx_goal, my_goal))
107  {
108  RCLCPP_WARN(logger_, "Goal Coordinates were outside map bounds");
109  return global_path;
110  }
111 
112  if (mx_start == mx_goal && my_start == my_goal) {
113  if (planner_->costmap_->getCost(mx_start, my_start) == nav2_costmap_2d::LETHAL_OBSTACLE) {
114  RCLCPP_WARN(logger_, "Failed to create a unique pose path because of obstacles");
115  return global_path;
116  }
117  global_path.header.stamp = clock_->now();
118  global_path.header.frame_id = global_frame_;
119  geometry_msgs::msg::PoseStamped pose;
120  pose.header = global_path.header;
121  pose.pose.position.z = 0.0;
122 
123  pose.pose = start.pose;
124  // if we have a different start and goal orientation, set the unique path pose to the goal
125  // orientation, unless use_final_approach_orientation=true where we need it to be the start
126  // orientation to avoid movement from the local planner
127  if (start.pose.orientation != goal.pose.orientation && !use_final_approach_orientation_) {
128  pose.pose.orientation = goal.pose.orientation;
129  }
130  global_path.poses.push_back(pose);
131  return global_path;
132  }
133 
134  planner_->setStartAndGoal(start, goal);
135  RCLCPP_DEBUG(
136  logger_, "Got the src and dst... (%i, %i) && (%i, %i)",
137  planner_->src_.x, planner_->src_.y, planner_->dst_.x, planner_->dst_.y);
138  getPlan(global_path);
139  // check if a plan is generated
140  size_t plan_size = global_path.poses.size();
141  if (plan_size > 0) {
142  global_path.poses.back().pose.orientation = goal.pose.orientation;
143  }
144 
145  // If use_final_approach_orientation=true, interpolate the last pose orientation from the
146  // previous pose to set the orientation to the 'final approach' orientation of the robot so
147  // it does not rotate.
148  // And deal with corner case of plan of length 1
149  if (use_final_approach_orientation_) {
150  if (plan_size == 1) {
151  global_path.poses.back().pose.orientation = start.pose.orientation;
152  } else if (plan_size > 1) {
153  double dx, dy, theta;
154  auto last_pose = global_path.poses.back().pose.position;
155  auto approach_pose = global_path.poses[plan_size - 2].pose.position;
156  dx = last_pose.x - approach_pose.x;
157  dy = last_pose.y - approach_pose.y;
158  theta = atan2(dy, dx);
159  global_path.poses.back().pose.orientation =
160  nav2_util::geometry_utils::orientationAroundZAxis(theta);
161  }
162  }
163 
164  auto stop_time = std::chrono::steady_clock::now();
165  auto dur = std::chrono::duration_cast<std::chrono::microseconds>(stop_time - start_time);
166  RCLCPP_DEBUG(logger_, "the time taken is : %i", static_cast<int>(dur.count()));
167  RCLCPP_DEBUG(logger_, "the nodes_opened are: %i", planner_->nodes_opened);
168  return global_path;
169 }
170 
171 void ThetaStarPlanner::getPlan(nav_msgs::msg::Path & global_path)
172 {
173  std::vector<coordsW> path;
174  if (planner_->isUnsafeToPlan()) {
175  RCLCPP_ERROR(logger_, "Either of the start or goal pose are an obstacle! ");
176  global_path.poses.clear();
177  } else if (planner_->generatePath(path)) {
178  global_path = linearInterpolation(path, planner_->costmap_->getResolution());
179  } else {
180  RCLCPP_ERROR(logger_, "Could not generate path between the given poses");
181  global_path.poses.clear();
182  }
183  global_path.header.stamp = clock_->now();
184  global_path.header.frame_id = global_frame_;
185 }
186 
188  const std::vector<coordsW> & raw_path,
189  const double & dist_bw_points)
190 {
191  nav_msgs::msg::Path pa;
192 
193  geometry_msgs::msg::PoseStamped p1;
194  for (unsigned int j = 0; j < raw_path.size() - 1; j++) {
195  coordsW pt1 = raw_path[j];
196  p1.pose.position.x = pt1.x;
197  p1.pose.position.y = pt1.y;
198  pa.poses.push_back(p1);
199 
200  coordsW pt2 = raw_path[j + 1];
201  double distance = std::hypot(pt2.x - pt1.x, pt2.y - pt1.y);
202  int loops = static_cast<int>(distance / dist_bw_points);
203  double sin_alpha = (pt2.y - pt1.y) / distance;
204  double cos_alpha = (pt2.x - pt1.x) / distance;
205  for (int k = 1; k < loops; k++) {
206  p1.pose.position.x = pt1.x + k * dist_bw_points * cos_alpha;
207  p1.pose.position.y = pt1.y + k * dist_bw_points * sin_alpha;
208  pa.poses.push_back(p1);
209  }
210  }
211 
212  return pa;
213 }
214 
215 rcl_interfaces::msg::SetParametersResult
216 ThetaStarPlanner::dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters)
217 {
218  rcl_interfaces::msg::SetParametersResult result;
219  for (auto parameter : parameters) {
220  const auto & type = parameter.get_type();
221  const auto & name = parameter.get_name();
222 
223  if (type == ParameterType::PARAMETER_INTEGER) {
224  if (name == name_ + ".how_many_corners") {
225  planner_->how_many_corners_ = parameter.as_int();
226  }
227  } else if (type == ParameterType::PARAMETER_DOUBLE) {
228  if (name == name_ + ".w_euc_cost") {
229  planner_->w_euc_cost_ = parameter.as_double();
230  } else if (name == name_ + ".w_traversal_cost") {
231  planner_->w_traversal_cost_ = parameter.as_double();
232  }
233  } else if (type == ParameterType::PARAMETER_BOOL) {
234  if (name == name_ + ".use_final_approach_orientation") {
235  use_final_approach_orientation_ = parameter.as_bool();
236  } else if (name == name_ + ".allow_unknown") {
237  planner_->allow_unknown_ = parameter.as_bool();
238  }
239  }
240  }
241 
242  result.successful = true;
243  return result;
244 }
245 
246 } // namespace nav2_theta_star_planner
247 
248 #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
nav_msgs::msg::Path createPlan(const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal) override
Method create the plan from a starting and ending goal.
void cleanup() override
Method to cleanup resources used on shutdown.
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 getPlan(nav_msgs::msg::Path &global_path)
the function responsible for calling the algorithm and retrieving a path from it
void activate() override
Method to active planner and any threads involved in execution.