Skip to content

Commit

Permalink
switch to unique_ptr
Browse files Browse the repository at this point in the history
  • Loading branch information
Guillaume Doisy committed May 17, 2023
1 parent 367aa44 commit 07be02d
Show file tree
Hide file tree
Showing 3 changed files with 5 additions and 5 deletions.
2 changes: 1 addition & 1 deletion nav2_smac_planner/include/nav2_smac_planner/a_star.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -110,7 +110,7 @@ class AStarAlgorithm
*/
bool createPath(
CoordinateVector & path, int & num_iterations, const float & tolerance,
std::shared_ptr<std::vector<std::tuple<float, float>>> expansions_log = nullptr);
std::vector<std::tuple<float, float>> * expansions_log = nullptr);

/**
* @brief Sets the collision checker to use
Expand Down
2 changes: 1 addition & 1 deletion nav2_smac_planner/src/a_star.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -224,7 +224,7 @@ template<typename NodeT>
bool AStarAlgorithm<NodeT>::createPath(
CoordinateVector & path, int & iterations,
const float & tolerance,
std::shared_ptr<std::vector<std::tuple<float, float>>> expansions_log)
std::vector<std::tuple<float, float>> * expansions_log)
{
steady_clock::time_point start_time = steady_clock::now();
_tolerance = tolerance;
Expand Down
6 changes: 3 additions & 3 deletions nav2_smac_planner/src/smac_planner_hybrid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -342,14 +342,14 @@ nav_msgs::msg::Path SmacPlannerHybrid::createPlan(
NodeHybrid::CoordinateVector path;
int num_iterations = 0;
std::string error;
std::shared_ptr<std::vector<std::tuple<float, float>>> expansions = nullptr;
std::unique_ptr<std::vector<std::tuple<float, float>>> expansions = nullptr;
try {
if (_viz_expansions) {
expansions = std::make_shared<std::vector<std::tuple<float, float>>>();
expansions = std::make_unique<std::vector<std::tuple<float, float>>>();
}
if (!_a_star->createPath(
path, num_iterations, _tolerance / static_cast<float>(costmap->getResolution()),
expansions))
expansions.get()))
{
if (num_iterations < _a_star->getMaxIterations()) {
error = std::string("no valid path found");
Expand Down

0 comments on commit 07be02d

Please sign in to comment.