|
36 | 36 |
|
37 | 37 | #include "ompl/geometric/planners/rrt/STRRTstar.h" |
38 | 38 | #include <ompl/util/Exception.h> |
| 39 | +#include <ompl/base/ScopedState.h> |
39 | 40 |
|
40 | 41 | ompl::geometric::STRRTstar::STRRTstar(const ompl::base::SpaceInformationPtr &si) |
41 | 42 | : Planner(si, "SpaceTimeRRT"), sampler_(&(*si), startMotion_, goalMotions_, newBatchGoalMotions_, sampleOldBatch_) |
@@ -153,7 +154,9 @@ ompl::base::PlannerStatus ompl::geometric::STRRTstar::solve(const ompl::base::Pl |
153 | 154 | (int)(tStart_->size() + tGoal_->size())); |
154 | 155 |
|
155 | 156 | 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(); |
157 | 160 |
|
158 | 161 | std::vector<Motion *> nbh; |
159 | 162 | const ompl::base::ReportIntermediateSolutionFn intermediateSolutionCallback = |
@@ -402,7 +405,7 @@ ompl::base::PlannerStatus ompl::geometric::STRRTstar::solve(const ompl::base::Pl |
402 | 405 | } |
403 | 406 | } |
404 | 407 |
|
405 | | - si_->freeState(tgi.xstate); |
| 408 | + // No need to manually free tgi.xstate anymore - ScopedState handles it |
406 | 409 | si_->freeState(rstate); |
407 | 410 | delete rmotion; |
408 | 411 |
|
@@ -769,7 +772,9 @@ ompl::base::ConditionalStateSampler::Motion *ompl::geometric::STRRTstar::pruneGo |
769 | 772 | if (costSoFar + costToGo <= upperTimeBound_) |
770 | 773 | { |
771 | 774 | 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(); |
773 | 778 | tgi.start = false; |
774 | 779 | std::vector<Motion *> nbh; |
775 | 780 | GrowState gsc = growTree(tGoal_, tgi, queue.front(), nbh, true); |
|
0 commit comments