18 #include "geometry_msgs/msg/pose_stamped.hpp"
20 #include "nav2_core/planner_exceptions.hpp"
21 #include "nav2_theta_star_planner/theta_star.hpp"
26 ThetaStar::ThetaStar()
27 : w_traversal_cost_(1.0),
29 w_heuristic_cost_(1.0),
34 terminal_checking_interval_(5000),
40 void ThetaStar::setStartAndGoal(
41 const geometry_msgs::msg::PoseStamped & start,
42 const geometry_msgs::msg::PoseStamped & goal)
44 unsigned int s[2], d[2];
45 costmap_->worldToMap(start.pose.position.x, start.pose.position.y, s[0], s[1]);
46 costmap_->worldToMap(goal.pose.position.x, goal.pose.position.y, d[0], d[1]);
48 src_ = {
static_cast<int>(s[0]),
static_cast<int>(s[1])};
49 dst_ = {
static_cast<int>(d[0]),
static_cast<int>(d[1])};
52 bool ThetaStar::generatePath(std::vector<coordsW> & raw_path, std::function<
bool()> cancel_checker)
55 addToNodesData(index_generated_);
56 double src_g_cost = getTraversalCost(src_.x, src_.y), src_h_cost = getHCost(src_.x, src_.y);
57 nodes_data_[index_generated_] =
58 {src_.x, src_.y, src_g_cost, src_h_cost, &nodes_data_[index_generated_],
true,
59 src_g_cost + src_h_cost};
60 queue_.push({&nodes_data_[index_generated_]});
61 addIndex(src_.x, src_.y, &nodes_data_[index_generated_]);
62 tree_node * curr_data = &nodes_data_[index_generated_];
66 while (!queue_.empty()) {
69 if (nodes_opened % terminal_checking_interval_ == 0 && cancel_checker()) {
74 if (isGoal(*curr_data)) {
78 resetParent(curr_data);
79 setNeighbors(curr_data);
81 curr_data = queue_.top();
90 backtrace(raw_path, curr_data);
98 double g_cost, los_cost = 0;
99 curr_data->is_in_queue =
false;
100 const tree_node * curr_par = curr_data->parent_id;
101 const tree_node * maybe_par = curr_par->parent_id;
103 if (losCheck(curr_data->x, curr_data->y, maybe_par->x, maybe_par->y, los_cost)) {
104 g_cost = maybe_par->g +
105 getEuclideanCost(curr_data->x, curr_data->y, maybe_par->x, maybe_par->y) + los_cost;
107 if (g_cost < curr_data->g) {
108 curr_data->parent_id = maybe_par;
109 curr_data->g = g_cost;
110 curr_data->f = g_cost + curr_data->h;
115 void ThetaStar::setNeighbors(
const tree_node * curr_data)
119 double g_cost, h_cost, cal_cost;
121 for (
int i = 0; i < how_many_corners_; i++) {
122 mx = curr_data->x + moves[i].x;
123 my = curr_data->y + moves[i].y;
125 if (withinLimits(mx, my)) {
126 if (!isSafe(mx, my)) {
133 g_cost = curr_data->g + getEuclideanCost(curr_data->x, curr_data->y, mx, my) +
134 getTraversalCost(mx, my);
136 m_id = getIndex(mx, my);
138 if (m_id ==
nullptr) {
139 addToNodesData(index_generated_);
140 m_id = &nodes_data_[index_generated_];
141 addIndex(mx, my, m_id);
147 h_cost = getHCost(mx, my);
148 cal_cost = g_cost + h_cost;
149 if (exp_node->f > cal_cost) {
150 exp_node->g = g_cost;
151 exp_node->h = h_cost;
152 exp_node->f = cal_cost;
153 exp_node->parent_id = curr_data;
154 if (!exp_node->is_in_queue) {
157 exp_node->is_in_queue =
true;
164 void ThetaStar::backtrace(std::vector<coordsW> & raw_points,
const tree_node * curr_n)
const
166 std::vector<coordsW> path_rev;
169 costmap_->mapToWorld(curr_n->x, curr_n->y, world.x, world.y);
170 path_rev.push_back(world);
171 if (path_rev.size() > 1) {
172 curr_n = curr_n->parent_id;
174 }
while (curr_n->parent_id != curr_n);
175 costmap_->mapToWorld(curr_n->x, curr_n->y, world.x, world.y);
176 path_rev.push_back(world);
178 raw_points.reserve(path_rev.size());
179 for (
int i =
static_cast<int>(path_rev.size()) - 1; i >= 0; i--) {
180 raw_points.push_back(path_rev[i]);
184 bool ThetaStar::losCheck(
185 const int & x0,
const int & y0,
const int & x1,
const int & y1,
186 double & sl_cost)
const
191 int dy = abs(y1 - y0), dx = abs(x1 - x0), f = 0;
193 sx = x1 > x0 ? 1 : -1;
194 sy = y1 > y0 ? 1 : -1;
196 int u_x = (sx - 1) / 2;
197 int u_y = (sy - 1) / 2;
205 if (!isSafe(cx + u_x, cy + u_y, sl_cost)) {
211 if (f != 0 && !isSafe(cx + u_x, cy + u_y, sl_cost)) {
214 if (dy == 0 && !isSafe(cx + u_x, cy, sl_cost) && !isSafe(cx + u_x, cy - 1, sl_cost)) {
223 if (!isSafe(cx + u_x, cy + u_y, sl_cost)) {
229 if (f != 0 && !isSafe(cx + u_x, cy + u_y, sl_cost)) {
232 if (dx == 0 && !isSafe(cx, cy + u_y, sl_cost) && !isSafe(cx - 1, cy + u_y, sl_cost)) {
241 void ThetaStar::resetContainers()
243 index_generated_ = 0;
244 int last_size_x = size_x_;
245 int last_size_y = size_y_;
246 int curr_size_x =
static_cast<int>(costmap_->getSizeInCellsX());
247 int curr_size_y =
static_cast<int>(costmap_->getSizeInCellsY());
248 if (((last_size_x != curr_size_x) || (last_size_y != curr_size_y)) &&
249 static_cast<int>(node_position_.size()) < (curr_size_x * curr_size_y))
251 initializePosn(curr_size_y * curr_size_x - last_size_y * last_size_x);
252 nodes_data_.reserve(curr_size_x * curr_size_y);
256 size_x_ = curr_size_x;
257 size_y_ = curr_size_y;
260 void ThetaStar::initializePosn(
int size_inc)
262 if (!node_position_.empty()) {
263 for (
int i = 0; i < size_x_ * size_y_; i++) {
264 node_position_[i] =
nullptr;
268 for (
int i = 0; i < size_inc; i++) {
269 node_position_.push_back(
nullptr);
273 void ThetaStar::clearStart()
275 unsigned int mx_start =
static_cast<unsigned int>(src_.x);
276 unsigned int my_start =
static_cast<unsigned int>(src_.y);
277 costmap_->setCost(mx_start, my_start, nav2_costmap_2d::FREE_SPACE);