From: Zachary K. <za...@ri...> - 2021-08-11 14:45:09
|
Emre, Your setup on paper sounds like it should work. Some ideas: 1. Make sure that the sampler allocated through allocDefaultStateSampler is for the correct space if you are using the constrained state space. That is, make sure that the samplers are sampling for the appropriate state types. A segfault could be occuring due to using a constrained state (which wraps the underlying state) in the underlying space and vice versa. 2. I recommend that you use GoalLazySamples <https://ompl.kavrakilab.org/classompl_1_1base_1_1GoalLazySamples.html> (and implement a GoalSamplingFn) rather than GoalSampleableRegion, as it could take a while to find a constraint satisfying configuration with projection-based sampling. 3. I would also recommend not using the ProjectedStateSampler and instead just using the state space sampler and constraint directly, as you should check if the constraint is satisfied before returning the found configuration as a valid goal. All the ProjectedStateSampler does is a) call the underlying space sampler, b) project using the constraint, and c) check if bounds are satisfied. Best, Zak On 8/10/21 3:48 PM, Emre Cemal Gönen (Student) wrote: > Hello, > > I try to define a GoalSampleableRegion for a constrained planning > problem. Since the goal configuration includes additional constraints > for the planning constraints, I define two constraint objects for both > planning and goal. My idea is to create a motion plan using planning > constraints, and the goal region is defined based on the samples > generated from the goal constraints. > > For the definition of the GoalSampleableRegion, > > * distanceGoal method is chosen as a parameter of > goal_constraint.distance(state) > * sampleGoal method tries to use available samplers, which my > question is > > For sampling, rather than creating my own sampling method, I prefer to > use available samplers that are used for the planning of constrained > planning problems. I tried to use ProjectedStateSampler that takes > Constrained State Space of the goal constraint and > allocDefaultStateSampler from the state space as StateSamplerPtr. When > I call sampleUniform() method from the ProjectedStateSampler I > defined, I get the Segmentation fault (core dumped) error. Do you > think I do something wrong? Or, are there any ways to do it more > conveniently to solve my problem? > > Thank you, > Kindest Regards, > E. Cemal Gonen > > > -- > *EMRE CEMAL GÖNEN* > YÜKSEK LİSANS ÖĞRENCİSİ > GRADUATE STUDENT > > ------------------------------------------------------------------------ > Sabancı Üniversitesi > Üniversite Caddesi No:27 > 34956 Orta Mahalle > Tuzla - İstanbul > > *T* 0 216 483 90 00 - 2331 > *www.sabanciuniv.edu* <https://www.sabanciuniv.edu/> > > <http://www.sabanciuniv.edu> > > > image.gif > > > _______________________________________________ > ompl-users mailing list > omp...@li... > https://lists.sourceforge.net/lists/listinfo/ompl-users |