16 #include "nav2_core/planner_exceptions.hpp"
17 #include "nav2_theta_star_planner/theta_star.hpp"
22 ThetaStar::ThetaStar()
23 : w_traversal_cost_(1.0),
25 w_heuristic_cost_(1.0),
30 terminal_checking_interval_(5000),
36 void ThetaStar::setStartAndGoal(
37 const geometry_msgs::msg::PoseStamped & start,
38 const geometry_msgs::msg::PoseStamped & goal)
40 unsigned int s[2], d[2];
41 costmap_->worldToMap(start.pose.position.x, start.pose.position.y, s[0], s[1]);
42 costmap_->worldToMap(goal.pose.position.x, goal.pose.position.y, d[0], d[1]);
44 src_ = {
static_cast<int>(s[0]),
static_cast<int>(s[1])};
45 dst_ = {
static_cast<int>(d[0]),
static_cast<int>(d[1])};
48 bool ThetaStar::generatePath(std::vector<coordsW> & raw_path, std::function<
bool()> cancel_checker)
51 addToNodesData(index_generated_);
52 double src_g_cost = getTraversalCost(src_.x, src_.y), src_h_cost = getHCost(src_.x, src_.y);
53 nodes_data_[index_generated_] =
54 {src_.x, src_.y, src_g_cost, src_h_cost, &nodes_data_[index_generated_],
true,
55 src_g_cost + src_h_cost};
56 queue_.push({&nodes_data_[index_generated_]});
57 addIndex(src_.x, src_.y, &nodes_data_[index_generated_]);
58 tree_node * curr_data = &nodes_data_[index_generated_];
62 while (!queue_.empty()) {
65 if (nodes_opened % terminal_checking_interval_ == 0 && cancel_checker()) {
70 if (isGoal(*curr_data)) {
74 resetParent(curr_data);
75 setNeighbors(curr_data);
77 curr_data = queue_.top();
86 backtrace(raw_path, curr_data);
94 double g_cost, los_cost = 0;
95 curr_data->is_in_queue =
false;
96 const tree_node * curr_par = curr_data->parent_id;
97 const tree_node * maybe_par = curr_par->parent_id;
99 if (losCheck(curr_data->x, curr_data->y, maybe_par->x, maybe_par->y, los_cost)) {
100 g_cost = maybe_par->g +
101 getEuclideanCost(curr_data->x, curr_data->y, maybe_par->x, maybe_par->y) + los_cost;
103 if (g_cost < curr_data->g) {
104 curr_data->parent_id = maybe_par;
105 curr_data->g = g_cost;
106 curr_data->f = g_cost + curr_data->h;
111 void ThetaStar::setNeighbors(
const tree_node * curr_data)
115 double g_cost, h_cost, cal_cost;
117 for (
int i = 0; i < how_many_corners_; i++) {
118 mx = curr_data->x + moves[i].x;
119 my = curr_data->y + moves[i].y;
121 if (withinLimits(mx, my)) {
122 if (!isSafe(mx, my)) {
129 g_cost = curr_data->g + getEuclideanCost(curr_data->x, curr_data->y, mx, my) +
130 getTraversalCost(mx, my);
132 m_id = getIndex(mx, my);
134 if (m_id ==
nullptr) {
135 addToNodesData(index_generated_);
136 m_id = &nodes_data_[index_generated_];
137 addIndex(mx, my, m_id);
143 h_cost = getHCost(mx, my);
144 cal_cost = g_cost + h_cost;
145 if (exp_node->f > cal_cost) {
146 exp_node->g = g_cost;
147 exp_node->h = h_cost;
148 exp_node->f = cal_cost;
149 exp_node->parent_id = curr_data;
150 if (!exp_node->is_in_queue) {
153 exp_node->is_in_queue =
true;
160 void ThetaStar::backtrace(std::vector<coordsW> & raw_points,
const tree_node * curr_n)
const
162 std::vector<coordsW> path_rev;
165 costmap_->mapToWorld(curr_n->x, curr_n->y, world.x, world.y);
166 path_rev.push_back(world);
167 if (path_rev.size() > 1) {
168 curr_n = curr_n->parent_id;
170 }
while (curr_n->parent_id != curr_n);
171 costmap_->mapToWorld(curr_n->x, curr_n->y, world.x, world.y);
172 path_rev.push_back(world);
174 raw_points.reserve(path_rev.size());
175 for (
int i =
static_cast<int>(path_rev.size()) - 1; i >= 0; i--) {
176 raw_points.push_back(path_rev[i]);
180 bool ThetaStar::losCheck(
181 const int & x0,
const int & y0,
const int & x1,
const int & y1,
182 double & sl_cost)
const
187 int dy = abs(y1 - y0), dx = abs(x1 - x0), f = 0;
189 sx = x1 > x0 ? 1 : -1;
190 sy = y1 > y0 ? 1 : -1;
192 int u_x = (sx - 1) / 2;
193 int u_y = (sy - 1) / 2;
201 if (!isSafe(cx + u_x, cy + u_y, sl_cost)) {
207 if (f != 0 && !isSafe(cx + u_x, cy + u_y, sl_cost)) {
210 if (dy == 0 && !isSafe(cx + u_x, cy, sl_cost) && !isSafe(cx + u_x, cy - 1, sl_cost)) {
219 if (!isSafe(cx + u_x, cy + u_y, sl_cost)) {
225 if (f != 0 && !isSafe(cx + u_x, cy + u_y, sl_cost)) {
228 if (dx == 0 && !isSafe(cx, cy + u_y, sl_cost) && !isSafe(cx - 1, cy + u_y, sl_cost)) {
237 void ThetaStar::resetContainers()
239 index_generated_ = 0;
240 int last_size_x = size_x_;
241 int last_size_y = size_y_;
242 int curr_size_x =
static_cast<int>(costmap_->getSizeInCellsX());
243 int curr_size_y =
static_cast<int>(costmap_->getSizeInCellsY());
244 if (((last_size_x != curr_size_x) || (last_size_y != curr_size_y)) &&
245 static_cast<int>(node_position_.size()) < (curr_size_x * curr_size_y))
247 initializePosn(curr_size_y * curr_size_x - last_size_y * last_size_x);
248 nodes_data_.reserve(curr_size_x * curr_size_y);
252 size_x_ = curr_size_x;
253 size_y_ = curr_size_y;
256 void ThetaStar::initializePosn(
int size_inc)
258 if (!node_position_.empty()) {
259 for (
int i = 0; i < size_x_ * size_y_; i++) {
260 node_position_[i] =
nullptr;
264 for (
int i = 0; i < size_inc; i++) {
265 node_position_.push_back(
nullptr);
269 void ThetaStar::clearStart()
271 unsigned int mx_start =
static_cast<unsigned int>(src_.x);
272 unsigned int my_start =
static_cast<unsigned int>(src_.y);
273 costmap_->setCost(mx_start, my_start, nav2_costmap_2d::FREE_SPACE);