Skip to content

Commit

Permalink
Merge 6a2ea03 into 6f82f5f
Browse files Browse the repository at this point in the history
  • Loading branch information
jkflying committed Feb 5, 2020
2 parents 6f82f5f + 6a2ea03 commit 399e06a
Show file tree
Hide file tree
Showing 3 changed files with 19 additions and 6 deletions.
1 change: 1 addition & 0 deletions local_planner/include/local_planner/tree_node.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ class TreeNode {
float heuristic_;
int origin_;
bool closed_;
int depth_;

TreeNode();
TreeNode(int from, const Eigen::Vector3f& pos, const Eigen::Vector3f& vel);
Expand Down
20 changes: 16 additions & 4 deletions local_planner/src/nodes/star_planner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,8 +60,6 @@ void StarPlanner::buildLookAheadTree() {
for (int n = 0; n < n_expanded_nodes_ && is_expanded_node; n++) {
Eigen::Vector3f origin_position = tree_[origin].getPosition();
Eigen::Vector3f origin_velocity = tree_[origin].getVelocity();
PolarPoint facing_goal = cartesianToPolarHistogram(goal_, origin_position);
float distance_to_goal = (goal_ - origin_position).norm();

histogram.setZero();
generateNewHistogram(histogram, cloud_, origin_position);
Expand Down Expand Up @@ -100,6 +98,7 @@ void StarPlanner::buildLookAheadTree() {
float h = treeHeuristicFunction(tree_.size() - 1);
tree_.back().heuristic_ = h;
tree_.back().total_cost_ = tree_[origin].total_cost_ - tree_[origin].heuristic_ + candidate.cost + h;
tree_.back().depth_ = tree_[origin].depth_ + 1;
children++;
}
}
Expand All @@ -125,8 +124,21 @@ void StarPlanner::buildLookAheadTree() {
cost_image_data.clear();
candidate_vector.clear();
}
// smoothing between trees
int tree_end = origin;

// find best node to follow, taking into account A* completion
int max_depth = 0;
int max_depth_index = 0;
for (size_t i = 0; i < tree_.size(); i++) {
if (!(tree_[i].closed_)) {
if (tree_[i].depth_ > max_depth) {
max_depth = tree_[i].depth_;
max_depth_index = i;
}
}
}

// build final tree
int tree_end = max_depth_index;
path_node_positions_.clear();
while (tree_end > 0) {
path_node_positions_.push_back(tree_[tree_end].getPosition());
Expand Down
4 changes: 2 additions & 2 deletions local_planner/src/nodes/tree_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,13 +2,13 @@

namespace avoidance {

TreeNode::TreeNode() : total_cost_{0.0f}, heuristic_{0.0f}, origin_{0}, closed_{false} {
TreeNode::TreeNode() : total_cost_{0.0f}, heuristic_{0.0f}, origin_{0}, closed_{false}, depth_(0) {
position_ = Eigen::Vector3f::Zero();
velocity_ = Eigen::Vector3f::Zero();
}

TreeNode::TreeNode(int from, const Eigen::Vector3f& pos, const Eigen::Vector3f& vel)
: total_cost_{0.0f}, heuristic_{0.0f}, origin_{from}, closed_{false} {
: total_cost_{0.0f}, heuristic_{0.0f}, origin_{from}, closed_{false}, depth_(0) {
position_ = pos;
velocity_ = vel;
}
Expand Down

0 comments on commit 399e06a

Please sign in to comment.