model_based_planning_context.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
37 #pragma once
38 
42 
43 #include <ompl/geometric/SimpleSetup.h>
44 #include <ompl/tools/benchmark/Benchmark.h>
45 #include <ompl/tools/multiplan/ParallelPlan.h>
46 #include <ompl/base/StateStorage.h>
47 
48 namespace ompl_interface
49 {
50 namespace ob = ompl::base;
51 namespace og = ompl::geometric;
52 namespace ot = ompl::tools;
53 
54 MOVEIT_CLASS_FORWARD(ModelBasedPlanningContext); // Defines ModelBasedPlanningContextPtr, ConstPtr, WeakPtr... etc
55 MOVEIT_CLASS_FORWARD(ConstraintsLibrary); // Defines ConstraintsLibraryPtr, ConstPtr, WeakPtr... etc
56 
57 struct ModelBasedPlanningContextSpecification;
58 typedef std::function<ob::PlannerPtr(const ompl::base::SpaceInformationPtr& si, const std::string& name,
59  const ModelBasedPlanningContextSpecification& spec)>
61 typedef std::function<ConfiguredPlannerAllocator(const std::string& planner_type)> ConfiguredPlannerSelector;
62 
63 struct ModelBasedPlanningContextSpecification
64 {
65  std::map<std::string, std::string> config_;
67  constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_;
68 
69  ModelBasedStateSpacePtr state_space_;
70  og::SimpleSetupPtr ompl_simple_setup_; // pass in the correct simple setup type
71 };
72 
73 class ModelBasedPlanningContext : public planning_interface::PlanningContext
74 {
75 public:
76  ModelBasedPlanningContext(const std::string& name, const ModelBasedPlanningContextSpecification& spec);
77 
79  {
80  }
81 
84 
85  void clear() override;
86  bool terminate() override;
87 
88  const ModelBasedPlanningContextSpecification& getSpecification() const
89  {
90  return spec_;
91  }
92 
93  const std::map<std::string, std::string>& getSpecificationConfig() const
94  {
95  return spec_.config_;
96  }
97 
98  void setSpecificationConfig(const std::map<std::string, std::string>& config)
99  {
100  spec_.config_ = config;
101  }
102 
103  const moveit::core::RobotModelConstPtr& getRobotModel() const
104  {
105  return spec_.state_space_->getRobotModel();
106  }
107 
109  {
110  return spec_.state_space_->getJointModelGroup();
111  }
112 
114  {
116  }
117 
118  const ModelBasedStateSpacePtr& getOMPLStateSpace() const
119  {
121  }
122 
123  const og::SimpleSetupPtr& getOMPLSimpleSetup() const
124  {
126  }
127 
128  og::SimpleSetupPtr& getOMPLSimpleSetup()
129  {
131  }
132 
133  const ot::Benchmark& getOMPLBenchmark() const
134  {
136  }
137 
138  ot::Benchmark& getOMPLBenchmark()
139  {
141  }
142 
143  const kinematic_constraints::KinematicConstraintSetPtr& getPathConstraints() const
144  {
146  }
147 
148  /* \brief Get the maximum number of sampling attempts allowed when sampling states is needed */
149  unsigned int getMaximumStateSamplingAttempts() const
150  {
152  }
153 
154  /* \brief Set the maximum number of sampling attempts allowed when sampling states is needed */
155  void setMaximumStateSamplingAttempts(unsigned int max_state_sampling_attempts)
156  {
157  max_state_sampling_attempts_ = max_state_sampling_attempts;
158  }
159 
160  /* \brief Get the maximum number of sampling attempts allowed when sampling goals is needed */
161  unsigned int getMaximumGoalSamplingAttempts() const
162  {
164  }
165 
166  /* \brief Set the maximum number of sampling attempts allowed when sampling goals is needed */
167  void setMaximumGoalSamplingAttempts(unsigned int max_goal_sampling_attempts)
168  {
169  max_goal_sampling_attempts_ = max_goal_sampling_attempts;
170  }
171 
172  /* \brief Get the maximum number of valid goal samples to store */
173  unsigned int getMaximumGoalSamples() const
174  {
176  }
177 
178  /* \brief Set the maximum number of valid goal samples to store */
179  void setMaximumGoalSamples(unsigned int max_goal_samples)
180  {
181  max_goal_samples_ = max_goal_samples;
182  }
183 
184  /* \brief Get the maximum number of planning threads allowed */
185  unsigned int getMaximumPlanningThreads() const
186  {
188  }
189 
190  /* \brief Set the maximum number of planning threads */
191  void setMaximumPlanningThreads(unsigned int max_planning_threads)
192  {
193  max_planning_threads_ = max_planning_threads;
194  }
195 
196  /* \brief Get the maximum solution segment length */
197  double getMaximumSolutionSegmentLength() const
198  {
200  }
201 
202  /* \brief Set the maximum solution segment length */
203  void setMaximumSolutionSegmentLength(double mssl)
204  {
206  }
207 
208  unsigned int getMinimumWaypointCount() const
209  {
211  }
212 
214  void setMinimumWaypointCount(unsigned int mwc)
215  {
217  }
218 
219  const constraint_samplers::ConstraintSamplerManagerPtr& getConstraintSamplerManager()
220  {
222  }
223 
224  void setConstraintSamplerManager(const constraint_samplers::ConstraintSamplerManagerPtr& csm)
225  {
227  }
228 
230 
231  void setProjectionEvaluator(const std::string& peval);
232 
233  void setPlanningVolume(const moveit_msgs::WorkspaceParameters& wparams);
234 
235  void setCompleteInitialState(const moveit::core::RobotState& complete_initial_robot_state);
236 
237  bool setGoalConstraints(const std::vector<moveit_msgs::Constraints>& goal_constraints,
238  const moveit_msgs::Constraints& path_constraints, moveit_msgs::MoveItErrorCodes* error);
239  bool setPathConstraints(const moveit_msgs::Constraints& path_constraints, moveit_msgs::MoveItErrorCodes* error);
240 
241  void setConstraintsApproximations(const ConstraintsLibraryPtr& constraints_library)
242  {
243  constraints_library_ = constraints_library;
244  }
245 
246  ConstraintsLibraryPtr getConstraintsLibraryNonConst()
247  {
248  return constraints_library_;
249  }
250 
251  const ConstraintsLibraryPtr& getConstraintsLibrary() const
252  {
253  return constraints_library_;
254  }
255 
256  bool simplifySolutions() const
257  {
258  return simplify_solutions_;
259  }
260 
261  void simplifySolutions(bool flag)
262  {
263  simplify_solutions_ = flag;
264  }
265 
266  void setInterpolation(bool flag)
267  {
268  interpolate_ = flag;
269  }
270 
271  void setHybridize(bool flag)
272  {
273  hybridize_ = flag;
274  }
275 
276  /* @brief Solve the planning problem. Return true if the problem is solved
277  @param timeout The time to spend on solving
278  @param count The number of runs to combine the paths of, in an attempt to generate better quality paths
279  */
280  const moveit_msgs::MoveItErrorCodes solve(double timeout, unsigned int count);
281 
282  /* @brief Benchmark the planning problem. Return true on successful saving of benchmark results
283  @param timeout The time to spend on solving
284  @param count The number of runs to average in the computation of the benchmark
285  @param filename The name of the file to which the benchmark results are to be saved (automatic names can be
286  provided if a name is not specified)
287  */
288  bool benchmark(double timeout, unsigned int count, const std::string& filename = "");
289 
290  /* @brief Get the amount of time spent computing the last plan */
291  double getLastPlanTime() const
292  {
294  }
295 
296  /* @brief Get the amount of time spent simplifying the last plan */
297  double getLastSimplifyTime() const
298  {
299  return last_simplify_time_;
300  }
301 
302  /* @brief Apply smoothing and try to simplify the plan
303  @param timeout The amount of time allowed to be spent on simplifying the plan*/
304  void simplifySolution(double timeout);
305 
306  /* @brief Interpolate the solution*/
307  void interpolateSolution();
308 
309  /* @brief Get the solution as a RobotTrajectory object*/
311 
312  void convertPath(const og::PathGeometric& pg, robot_trajectory::RobotTrajectory& traj) const;
313 
317 
321 
329  virtual void configure(const ros::NodeHandle& nh, bool use_constraints_approximations);
330 
331 protected:
332  void preSolve();
333  void postSolve();
334 
335  void startSampling();
336  void stopSampling();
337 
338  virtual ob::ProjectionEvaluatorPtr getProjectionEvaluator(const std::string& peval) const;
339  virtual ob::StateSamplerPtr allocPathConstrainedSampler(const ompl::base::StateSpace* ss) const;
340  virtual void useConfig();
341  virtual ob::GoalPtr constructGoal();
342 
343  /* @brief Construct a planner termination condition, by default a simple time limit
344  @param timeout The maximum time (in seconds) that can be used for planning
345  @param start The point in time from which planning is considered to have started
346 
347  An additional planner termination condition can be specified per planner
348  configuration in ompl_planning.yaml via the `termination_condition` parameter.
349  Possible values are:
350 
351  * `Iteration[num]`: Terminate after `num` iterations. Here, `num` should be replaced
352  with a positive integer.
353  * `CostConvergence[solutions_window,epsilon]`: Terminate after the cost (as specified
354  by an optimization objective) has converged. The parameter `solutions_window`
355  specifies the minimum number of solutions to use in deciding whether a planner has
356  converged. The parameter `epsilon` is the threshold to consider for convergence.
357  This should be a positive number close to 0. If the cumulative moving average does
358  not change by a relative fraction of epsilon after a new better solution is found,
359  convergence has been reached.
360  * `ExactSolution`: Terminate as soon as an exact solution is found or a timeout
361  occurs. This modifies the behavior of anytime/optimizing planners to terminate
362  upon discovering the first feasible solution.
363 
364  In all cases, the planner will terminate when either the user-specified termination
365  condition is satisfied or the time limit specified by `timeout` has been reached,
366  whichever occurs first.
367  */
368  virtual ob::PlannerTerminationCondition constructPlannerTerminationCondition(double timeout,
369  const ompl::time::point& start);
370 
371  void registerTerminationCondition(const ob::PlannerTerminationCondition& ptc);
373 
375  int32_t errorCode(const ompl::base::PlannerStatus& status);
376 
378 
380 
382  og::SimpleSetupPtr ompl_simple_setup_;
383 
385  ot::Benchmark ompl_benchmark_;
386 
388  ot::ParallelPlan ompl_parallel_plan_;
389 
390  std::vector<int> space_signature_;
391 
392  kinematic_constraints::KinematicConstraintSetPtr path_constraints_;
393  moveit_msgs::Constraints path_constraints_msg_;
394  std::vector<kinematic_constraints::KinematicConstraintSetPtr> goal_constraints_;
395 
396  const ob::PlannerTerminationCondition* ptc_;
397  std::mutex ptc_lock_;
398 
400  double last_plan_time_;
401 
403  double last_simplify_time_;
404 
407  unsigned int max_goal_samples_;
408 
412 
415 
417  unsigned int max_planning_threads_;
418 
422 
426 
429 
430  ConstraintsLibraryPtr constraints_library_;
431 
433 
434  // if false the final solution is not interpolated
436 
437  // if false parallel plan returns the first solution found
438  bool hybridize_;
439 };
440 } // namespace ompl_interface
ompl_interface::ModelBasedPlanningContext::terminate
bool terminate() override
Definition: model_based_planning_context.cpp:874
ompl_interface::ModelBasedPlanningContext::max_solution_segment_length_
double max_solution_segment_length_
Definition: model_based_planning_context.h:453
ompl_interface::ModelBasedPlanningContext::getJointModelGroup
const moveit::core::JointModelGroup * getJointModelGroup() const
Definition: model_based_planning_context.h:140
ompl_interface::ModelBasedPlanningContext::setHybridize
void setHybridize(bool flag)
Definition: model_based_planning_context.h:303
ompl_interface::ModelBasedPlanningContext::loadConstraintApproximations
bool loadConstraintApproximations(const ros::NodeHandle &nh)
Look up param server 'constraint_approximations' and use its value as the path to load constraint app...
Definition: model_based_planning_context.cpp:894
ompl_interface::ModelBasedPlanningContext::ompl_simple_setup_
og::SimpleSetupPtr ompl_simple_setup_
the OMPL planning context; this contains the problem definition and the planner used
Definition: model_based_planning_context.h:414
ompl_interface::ModelBasedPlanningContext::setConstraintsApproximations
void setConstraintsApproximations(const ConstraintsLibraryPtr &constraints_library)
Definition: model_based_planning_context.h:273
ompl_interface::ModelBasedPlanningContext::setConstraintSamplerManager
void setConstraintSamplerManager(const constraint_samplers::ConstraintSamplerManagerPtr &csm)
Definition: model_based_planning_context.h:256
ompl_interface::ModelBasedPlanningContext::useConfig
virtual void useConfig()
Definition: model_based_planning_context.cpp:256
planning_interface::MotionPlanResponse
ompl_interface::ModelBasedPlanningContext::startSampling
void startSampling()
Definition: model_based_planning_context.cpp:644
ompl_interface::ModelBasedPlanningContext::minimum_waypoint_count_
unsigned int minimum_waypoint_count_
Definition: model_based_planning_context.h:457
ompl_interface::ModelBasedPlanningContext::getMaximumSolutionSegmentLength
double getMaximumSolutionSegmentLength() const
Definition: model_based_planning_context.h:229
ompl_interface::ModelBasedPlanningContext::getOMPLSimpleSetup
const og::SimpleSetupPtr & getOMPLSimpleSetup() const
Definition: model_based_planning_context.h:155
ompl_interface::ModelBasedPlanningContext::interpolate_
bool interpolate_
Definition: model_based_planning_context.h:467
ompl_interface::ModelBasedPlanningContext::getLastPlanTime
double getLastPlanTime() const
Definition: model_based_planning_context.h:323
ompl_interface::ModelBasedPlanningContext::getProjectionEvaluator
virtual ob::ProjectionEvaluatorPtr getProjectionEvaluator(const std::string &peval) const
Definition: model_based_planning_context.cpp:154
ompl_interface::ModelBasedPlanningContext::setPlanningVolume
void setPlanningVolume(const moveit_msgs::WorkspaceParameters &wparams)
Definition: model_based_planning_context.cpp:388
ompl_interface::ModelBasedPlanningContext::space_signature_
std::vector< int > space_signature_
Definition: model_based_planning_context.h:422
ompl_interface
The MoveIt interface to OMPL.
Definition: constrained_goal_sampler.h:46
ompl_interface::ModelBasedPlanningContext::stopSampling
void stopSampling()
Definition: model_based_planning_context.cpp:654
ompl_interface::ModelBasedPlanningContext::max_goal_samples_
unsigned int max_goal_samples_
Definition: model_based_planning_context.h:439
planning_interface.h
ompl_interface::ModelBasedPlanningContextSpecification::constraint_sampler_manager_
constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_
Definition: model_based_planning_context.h:99
moveit::core::RobotState
ompl_interface::ModelBasedPlanningContext::simplifySolutions
bool simplifySolutions() const
Definition: model_based_planning_context.h:288
ompl_interface::ModelBasedPlanningContext::getSpecificationConfig
const std::map< std::string, std::string > & getSpecificationConfig() const
Definition: model_based_planning_context.h:125
ompl_interface::ModelBasedPlanningContext::ModelBasedPlanningContext
ModelBasedPlanningContext(const std::string &name, const ModelBasedPlanningContextSpecification &spec)
Definition: model_based_planning_context.cpp:80
model_based_state_space.h
robot_trajectory::RobotTrajectory
ompl_interface::ModelBasedPlanningContext::setSpecificationConfig
void setSpecificationConfig(const std::map< std::string, std::string > &config)
Definition: model_based_planning_context.h:130
ompl_interface::ModelBasedPlanningContext::getMaximumGoalSamples
unsigned int getMaximumGoalSamples() const
Definition: model_based_planning_context.h:205
ompl_interface::ModelBasedPlanningContext::setCompleteInitialState
void setCompleteInitialState(const moveit::core::RobotState &complete_initial_robot_state)
Definition: model_based_planning_context.cpp:554
ompl_interface::ModelBasedPlanningContext::convertPath
void convertPath(const og::PathGeometric &pg, robot_trajectory::RobotTrajectory &traj) const
Definition: model_based_planning_context.cpp:443
ompl_interface::ModelBasedPlanningContext::setMaximumSolutionSegmentLength
void setMaximumSolutionSegmentLength(double mssl)
Definition: model_based_planning_context.h:235
ompl_interface::ModelBasedPlanningContextSpecification::ompl_simple_setup_
og::SimpleSetupPtr ompl_simple_setup_
Definition: model_based_planning_context.h:102
ompl_interface::ConfiguredPlannerSelector
std::function< ConfiguredPlannerAllocator(const std::string &planner_type)> ConfiguredPlannerSelector
Definition: model_based_planning_context.h:93
ompl_interface::ModelBasedPlanningContext::~ModelBasedPlanningContext
~ModelBasedPlanningContext() override
Definition: model_based_planning_context.h:110
ompl_interface::ModelBasedPlanningContext::path_constraints_msg_
moveit_msgs::Constraints path_constraints_msg_
Definition: model_based_planning_context.h:425
ompl_interface::ModelBasedPlanningContext::constructPlannerTerminationCondition
virtual ob::PlannerTerminationCondition constructPlannerTerminationCondition(double timeout, const ompl::time::point &start)
Definition: model_based_planning_context.cpp:495
ompl_interface::ModelBasedPlanningContext::max_planning_threads_
unsigned int max_planning_threads_
when planning in parallel, this is the maximum number of threads to use at one time
Definition: model_based_planning_context.h:449
ompl_interface::ModelBasedPlanningContext::simplifySolution
void simplifySolution(double timeout)
Definition: model_based_planning_context.cpp:405
ompl_interface::ModelBasedPlanningContextSpecification::planner_selector_
ConfiguredPlannerSelector planner_selector_
Definition: model_based_planning_context.h:98
ompl_interface::ModelBasedPlanningContext::getSpecification
const ModelBasedPlanningContextSpecification & getSpecification() const
Definition: model_based_planning_context.h:120
ompl_interface::ModelBasedPlanningContext::getOMPLBenchmark
const ot::Benchmark & getOMPLBenchmark() const
Definition: model_based_planning_context.h:165
ompl_interface::ModelBasedPlanningContext::ptc_lock_
std::mutex ptc_lock_
Definition: model_based_planning_context.h:429
ompl_interface::ModelBasedPlanningContext::postSolve
void postSolve()
Definition: model_based_planning_context.cpp:675
ompl_interface::ModelBasedPlanningContext::setMaximumPlanningThreads
void setMaximumPlanningThreads(unsigned int max_planning_threads)
Definition: model_based_planning_context.h:223
ompl_interface::ModelBasedPlanningContext::setMinimumWaypointCount
void setMinimumWaypointCount(unsigned int mwc)
Get the minimum number of waypoints along the solution path.
Definition: model_based_planning_context.h:246
ompl_interface::ModelBasedPlanningContext::setGoalConstraints
bool setGoalConstraints(const std::vector< moveit_msgs::Constraints > &goal_constraints, const moveit_msgs::Constraints &path_constraints, moveit_msgs::MoveItErrorCodes *error)
Definition: model_based_planning_context.cpp:597
ompl_interface::ModelBasedPlanningContext::getConstraintsLibraryNonConst
ConstraintsLibraryPtr getConstraintsLibraryNonConst()
Definition: model_based_planning_context.h:278
ompl_interface::ModelBasedPlanningContext::getOMPLStateSpace
const ModelBasedStateSpacePtr & getOMPLStateSpace() const
Definition: model_based_planning_context.h:150
ompl_interface::ModelBasedPlanningContext::path_constraints_
kinematic_constraints::KinematicConstraintSetPtr path_constraints_
Definition: model_based_planning_context.h:424
ompl_interface::ModelBasedPlanningContext::multi_query_planning_enabled_
bool multi_query_planning_enabled_
when false, clears planners before running solve()
Definition: model_based_planning_context.h:460
ompl_interface::ModelBasedPlanningContext::getSolutionPath
bool getSolutionPath(robot_trajectory::RobotTrajectory &traj) const
Definition: model_based_planning_context.cpp:454
ompl_interface::ModelBasedPlanningContext::ptc_
const ob::PlannerTerminationCondition * ptc_
Definition: model_based_planning_context.h:428
ompl_interface::ModelBasedPlanningContext::spec_
ModelBasedPlanningContextSpecification spec_
Definition: model_based_planning_context.h:409
ompl_interface::ModelBasedPlanningContext::setPathConstraints
bool setPathConstraints(const moveit_msgs::Constraints &path_constraints, moveit_msgs::MoveItErrorCodes *error)
Definition: model_based_planning_context.cpp:586
ompl_interface::ModelBasedPlanningContext::interpolateSolution
void interpolateSolution()
Definition: model_based_planning_context.cpp:415
ompl_interface::ModelBasedPlanningContext::benchmark
bool benchmark(double timeout, unsigned int count, const std::string &filename="")
Definition: model_based_planning_context.cpp:626
ompl_interface::ModelBasedPlanningContext::getConstraintsLibrary
const ConstraintsLibraryPtr & getConstraintsLibrary() const
Definition: model_based_planning_context.h:283
ompl_interface::ModelBasedPlanningContext::getConstraintSamplerManager
const constraint_samplers::ConstraintSamplerManagerPtr & getConstraintSamplerManager()
Definition: model_based_planning_context.h:251
ompl_interface::ModelBasedPlanningContext::getMaximumPlanningThreads
unsigned int getMaximumPlanningThreads() const
Definition: model_based_planning_context.h:217
ompl_interface::ModelBasedPlanningContextSpecification
Definition: model_based_planning_context.h:95
ompl_interface::ModelBasedPlanningContext::unregisterTerminationCondition
void unregisterTerminationCondition()
Definition: model_based_planning_context.cpp:820
ompl_interface::ModelBasedPlanningContext::max_state_sampling_attempts_
unsigned int max_state_sampling_attempts_
Definition: model_based_planning_context.h:443
ompl_interface::ModelBasedPlanningContext::last_plan_time_
double last_plan_time_
the time spent computing the last plan
Definition: model_based_planning_context.h:432
ompl_interface::ModelBasedPlanningContext::getRobotModel
const moveit::core::RobotModelConstPtr & getRobotModel() const
Definition: model_based_planning_context.h:135
ompl_interface::ModelBasedPlanningContext::getMinimumWaypointCount
unsigned int getMinimumWaypointCount() const
Definition: model_based_planning_context.h:240
ompl_interface::ModelBasedPlanningContext::setVerboseStateValidityChecks
void setVerboseStateValidityChecks(bool flag)
Definition: model_based_planning_context.cpp:462
ompl_interface::ModelBasedPlanningContext::ompl_parallel_plan_
ot::ParallelPlan ompl_parallel_plan_
tool used to compute multiple plans in parallel; this uses the problem definition maintained by ompl_...
Definition: model_based_planning_context.h:420
ompl_interface::ModelBasedPlanningContext::setInterpolation
void setInterpolation(bool flag)
Definition: model_based_planning_context.h:298
ompl_interface::ModelBasedPlanningContextSpecification::config_
std::map< std::string, std::string > config_
Definition: model_based_planning_context.h:97
ompl_interface::ModelBasedPlanningContext::getPathConstraints
const kinematic_constraints::KinematicConstraintSetPtr & getPathConstraints() const
Definition: model_based_planning_context.h:175
ompl_interface::ModelBasedPlanningContext::max_goal_sampling_attempts_
unsigned int max_goal_sampling_attempts_
maximum number of attempts to be made at sampling a goal states
Definition: model_based_planning_context.h:446
constraint_sampler_manager.h
ompl_interface::ModelBasedPlanningContext::preSolve
void preSolve()
Definition: model_based_planning_context.cpp:664
ompl_interface::ModelBasedPlanningContext::configure
virtual void configure(const ros::NodeHandle &nh, bool use_constraints_approximations)
Configure ompl_simple_setup_ and optionally the constraints_library_.
Definition: model_based_planning_context.cpp:107
ompl_interface::ModelBasedPlanningContext::setMaximumGoalSamplingAttempts
void setMaximumGoalSamplingAttempts(unsigned int max_goal_sampling_attempts)
Definition: model_based_planning_context.h:199
ompl_interface::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(ConstraintApproximation)
ompl_interface::ModelBasedPlanningContext::registerTerminationCondition
void registerTerminationCondition(const ob::PlannerTerminationCondition &ptc)
Definition: model_based_planning_context.cpp:814
ompl_interface::ModelBasedPlanningContext::getMaximumGoalSamplingAttempts
unsigned int getMaximumGoalSamplingAttempts() const
Definition: model_based_planning_context.h:193
ompl_interface::ModelBasedPlanningContext::constraints_library_
ConstraintsLibraryPtr constraints_library_
Definition: model_based_planning_context.h:462
moveit::core::JointModelGroup
ompl_interface::ModelBasedPlanningContext::hybridize_
bool hybridize_
Definition: model_based_planning_context.h:470
ompl_interface::ConfiguredPlannerAllocator
std::function< ob::PlannerPtr(const ompl::base::SpaceInformationPtr &si, const std::string &name, const ModelBasedPlanningContextSpecification &spec)> ConfiguredPlannerAllocator
Definition: model_based_planning_context.h:89
ompl_interface::ModelBasedPlanningContext::saveConstraintApproximations
bool saveConstraintApproximations(const ros::NodeHandle &nh)
Look up param server 'constraint_approximations' and use its value as the path to save constraint app...
Definition: model_based_planning_context.cpp:882
ompl_interface::ModelBasedPlanningContext::last_simplify_time_
double last_simplify_time_
the time spent simplifying the last plan
Definition: model_based_planning_context.h:435
ompl_interface::ModelBasedPlanningContext::setMaximumStateSamplingAttempts
void setMaximumStateSamplingAttempts(unsigned int max_state_sampling_attempts)
Definition: model_based_planning_context.h:187
ompl_interface::ModelBasedPlanningContext::errorCode
int32_t errorCode(const ompl::base::PlannerStatus &status)
Convert OMPL PlannerStatus to moveit_msgs::msg::MoveItErrorCode.
Definition: model_based_planning_context.cpp:826
planning_interface::PlanningContext
ompl_interface::ModelBasedPlanningContext::simplify_solutions_
bool simplify_solutions_
Definition: model_based_planning_context.h:464
ompl_interface::ModelBasedPlanningContext::setMaximumGoalSamples
void setMaximumGoalSamples(unsigned int max_goal_samples)
Definition: model_based_planning_context.h:211
ompl_interface::ModelBasedPlanningContext::getMaximumStateSamplingAttempts
unsigned int getMaximumStateSamplingAttempts() const
Definition: model_based_planning_context.h:181
ompl_interface::ModelBasedPlanningContextSpecification::state_space_
ModelBasedStateSpacePtr state_space_
Definition: model_based_planning_context.h:101
ompl_interface::ModelBasedPlanningContext::complete_initial_robot_state_
moveit::core::RobotState complete_initial_robot_state_
Definition: model_based_planning_context.h:411
ompl_interface::ModelBasedPlanningContext::allocPathConstrainedSampler
virtual ob::StateSamplerPtr allocPathConstrainedSampler(const ompl::base::StateSpace *ss) const
Definition: model_based_planning_context.cpp:207
ros::NodeHandle
ompl_interface::ModelBasedPlanningContext::ompl_benchmark_
ot::Benchmark ompl_benchmark_
the OMPL tool for benchmarking planners
Definition: model_based_planning_context.h:417
ompl_interface::ModelBasedPlanningContext::constructGoal
virtual ob::GoalPtr constructGoal()
Definition: model_based_planning_context.cpp:468
planning_interface::MotionPlanDetailedResponse
ompl_interface::ModelBasedPlanningContext::solve
bool solve(planning_interface::MotionPlanResponse &res) override
Definition: model_based_planning_context.cpp:683
ompl_interface::ModelBasedPlanningContext::goal_constraints_
std::vector< kinematic_constraints::KinematicConstraintSetPtr > goal_constraints_
Definition: model_based_planning_context.h:426
ompl_interface::ModelBasedPlanningContext::getCompleteInitialRobotState
const moveit::core::RobotState & getCompleteInitialRobotState() const
Definition: model_based_planning_context.h:145
ompl_interface::ModelBasedPlanningContext::clear
void clear() override
Definition: model_based_planning_context.cpp:561
ompl_interface::ModelBasedPlanningContext::setProjectionEvaluator
void setProjectionEvaluator(const std::string &peval)
Definition: model_based_planning_context.cpp:141
ompl_interface::ModelBasedPlanningContext::getLastSimplifyTime
double getLastSimplifyTime() const
Definition: model_based_planning_context.h:329


ompl
Author(s): Ioan Sucan
autogenerated on Thu Apr 18 2024 02:24:37