Skip to content

Commit bc54b2f

Browse files
authored
Fix memory leaks in STRRTstar planner (ompl#1327)
1 parent 05aa440 commit bc54b2f

File tree

1 file changed

+8
-3
lines changed

1 file changed

+8
-3
lines changed

src/ompl/geometric/planners/rrt/src/STRRTstar.cpp

Lines changed: 8 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,7 @@
3636

3737
#include "ompl/geometric/planners/rrt/STRRTstar.h"
3838
#include <ompl/util/Exception.h>
39+
#include <ompl/base/ScopedState.h>
3940

4041
ompl::geometric::STRRTstar::STRRTstar(const ompl::base::SpaceInformationPtr &si)
4142
: Planner(si, "SpaceTimeRRT"), sampler_(&(*si), startMotion_, goalMotions_, newBatchGoalMotions_, sampleOldBatch_)
@@ -153,7 +154,9 @@ ompl::base::PlannerStatus ompl::geometric::STRRTstar::solve(const ompl::base::Pl
153154
(int)(tStart_->size() + tGoal_->size()));
154155

155156
TreeGrowingInfo tgi;
156-
tgi.xstate = si_->allocState();
157+
// Use ScopedState to ensure automatic cleanup even if exceptions are thrown
158+
ompl::base::ScopedState<> xstateScoped(si_);
159+
tgi.xstate = xstateScoped.get();
157160

158161
std::vector<Motion *> nbh;
159162
const ompl::base::ReportIntermediateSolutionFn intermediateSolutionCallback =
@@ -402,7 +405,7 @@ ompl::base::PlannerStatus ompl::geometric::STRRTstar::solve(const ompl::base::Pl
402405
}
403406
}
404407

405-
si_->freeState(tgi.xstate);
408+
// No need to manually free tgi.xstate anymore - ScopedState handles it
406409
si_->freeState(rstate);
407410
delete rmotion;
408411

@@ -769,7 +772,9 @@ ompl::base::ConditionalStateSampler::Motion *ompl::geometric::STRRTstar::pruneGo
769772
if (costSoFar + costToGo <= upperTimeBound_)
770773
{
771774
TreeGrowingInfo tgi{};
772-
tgi.xstate = si_->allocState();
775+
// Use ScopedState to ensure automatic cleanup even if exceptions are thrown
776+
ompl::base::ScopedState<> xstateScoped(si_);
777+
tgi.xstate = xstateScoped.get();
773778
tgi.start = false;
774779
std::vector<Motion *> nbh;
775780
GrowState gsc = growTree(tGoal_, tgi, queue.front(), nbh, true);

0 commit comments

Comments
 (0)