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