From ffe1298a38f8569a442c673202b2870976238184 Mon Sep 17 00:00:00 2001 From: root Date: Mon, 29 Apr 2024 20:42:22 +0000 Subject: [PATCH] change comparator sign --- src/navigation/navigation.cc | 19 +------------------ 1 file changed, 1 insertion(+), 18 deletions(-) diff --git a/src/navigation/navigation.cc b/src/navigation/navigation.cc index d89c644..cacb1af 100644 --- a/src/navigation/navigation.cc +++ b/src/navigation/navigation.cc @@ -154,7 +154,7 @@ struct PointCost { struct CompareCost { bool operator()(const PointCost& lhs, const PointCost& rhs) const { // Using > for max heap (change to < for min heap) - return lhs.cost < rhs.cost; + return lhs.cost > rhs.cost; } }; @@ -274,10 +274,6 @@ void Navigation::LoadVectorMap(const string& map_file){ //Assume map is given as global_costmap_.setCost(mx + j, my + k, std::max(cost, global_costmap_.getCost(mx + j, my + k))); inflation_cells[global_costmap_.getIndex(mx + j, my + k)] = std::max(cost, global_costmap_.getCost(mx + j, my + k)); } - // if((sqrt(pow(j, 2) + pow(k, 2)) <= cell_inflation_size) && (mx + j >= 0) && (mx + j < x_max) - // && (my + k >= 0) && (my + k < y_max)){ - // inflation_cells.insert(global_costmap_.getIndex(mx + j, my + k)); - // } } } } @@ -307,7 +303,6 @@ void Navigation::Enable(bool enable) { } void Navigation::SetNavGoal(const Vector2f& loc, float angle) { - cout << "set nav goal goto" << endl; nav_state_ = NavigationState::kGoto; nav_goal_loc_ = loc; nav_goal_angle_ = angle; @@ -587,7 +582,6 @@ vector Navigation::Plan(const Vector2f& initial, printf("No path found!\n"); } - // SimpleQueue intermediate_queue; // std::priority_queue, CompareCost> intermediate_queue; // unordered_map parent; @@ -662,8 +656,6 @@ vector Navigation::Plan(const Vector2f& initial, float dy = abs(goal_map_y - new_col); float heuristic_cost = max(dx, dy) + (sqrt(2.0) - 1.0) * min(dx, dy); - - // float heuristic_cost = (Vector2f(goal_map_x, goal_map_y) - Vector2f(new_row, new_col)).norm(); intermediate_queue.push(PointCost(neighbor_index, new_cost + heuristic_cost)); } } @@ -907,10 +899,6 @@ void Navigation::RunObstacleAvoidance(Vector2f& vel_cmd, float& ang_vel_cmd) { CumulativeFunctionTimer::Invocation invoke(&function_timer_); const bool debug = FLAGS_v > 1; - if(debug){ - printf("Running obstacle avoidance\n"); - } - // Handling potential carrot overrides from social nav Vector2f local_target = local_target_; if (nav_state_ == NavigationState::kOverride) { @@ -1035,7 +1023,6 @@ void Navigation::TurnInPlace(Vector2f& cmd_vel, float& cmd_angle_vel) { s * dTheta, 0, params_.dt); - cout << "turn in place test5: angle_vel = " << cmd_angle_vel << endl; } cmd_vel = {0, 0}; } @@ -1422,9 +1409,6 @@ bool Navigation::Run(const double& time, nav_state_ = NavigationState::kStopped; } } while (prev_state != nav_state_); - - cout << "before switch" << endl; - switch (nav_state_) { case NavigationState::kStopped: { @@ -1472,7 +1456,6 @@ bool Navigation::Run(const double& time, TurnInPlace(cmd_vel, cmd_angle_vel); } else { if (kDebug) printf("ObstAv\n"); - cout << "running obstacle avoidance original" << endl; RunObstacleAvoidance(cmd_vel, cmd_angle_vel); } }