|
67 | 67 | #include "ompl/base/objectives/MaximizeMinClearanceObjective.h"
|
68 | 68 | #include <ompl/geometric/planners/prm/LazyPRM.h>
|
69 | 69 |
|
70 |
| -#include <moveit/ompl_interface/ompl_optimization_objective_loader.h> |
71 |
| -#include <pluginlib/class_loader.hpp> |
72 |
| - |
73 | 70 |
|
74 | 71 | namespace ompl_interface
|
75 | 72 | {
|
@@ -102,6 +99,8 @@ ompl_interface::ModelBasedPlanningContext::ModelBasedPlanningContext(const std::
|
102 | 99 | complete_initial_robot_state_.update();
|
103 | 100 |
|
104 | 101 | constraints_library_ = std::make_shared<ConstraintsLibrary>(this);
|
| 102 | + |
| 103 | + constructOptimizationObjectives(); |
105 | 104 | }
|
106 | 105 |
|
107 | 106 | void ompl_interface::ModelBasedPlanningContext::configure(const rclcpp::Node::SharedPtr& node,
|
@@ -352,27 +351,18 @@ void ompl_interface::ModelBasedPlanningContext::useConfig()
|
352 | 351 | objective =
|
353 | 352 | std::make_shared<ompl::base::MaximizeMinClearanceObjective>(ompl_simple_setup_->getSpaceInformation());
|
354 | 353 | }
|
| 354 | + else if (optimization_objectives_.find(optimizer) != optimization_objectives_.end()) |
| 355 | + { |
| 356 | + objective = |
| 357 | + optimization_objectives_[optimizer]->getOptimizationObjective(ompl_simple_setup_->getSpaceInformation()); |
| 358 | + } |
355 | 359 | else
|
356 | 360 | {
|
357 |
| - pluginlib::ClassLoader<ompl_optimization_loader::OptimizationObjectiveLoader> poly_loader("moveit_core", "ompl_optimization_loader::OptimizationObjectiveLoader"); |
358 |
| - |
359 |
| - try |
360 |
| - { |
361 |
| - RCLCPP_DEBUG(LOGGER, "Using optimization objective : %s", optimizer.c_str()); |
362 |
| - std::shared_ptr<ompl_optimization_loader::OptimizationObjectiveLoader> obj = poly_loader.createSharedInstance(optimizer); |
| 361 | + RCLCPP_ERROR(LOGGER, "Unknown optimization objective for OMPL planner"); |
| 362 | + RCLCPP_ERROR(LOGGER, "Fall back to the default optimizer : PathLengthOptimizationObjective"); |
363 | 363 |
|
364 |
| - objective = obj->getOptimizationObjective(ompl_simple_setup_->getSpaceInformation()); |
365 |
| - |
366 |
| - } |
367 |
| - catch(pluginlib::PluginlibException& ex) |
368 |
| - { |
369 |
| - RCLCPP_ERROR(LOGGER, "The plugin failed to load for some reason. Error: %s", ex.what()); |
370 |
| - RCLCPP_ERROR(LOGGER, "Fall back to the default optimizer"); |
371 |
| - |
372 |
| - objective = |
373 |
| - std::make_shared<ompl::base::PathLengthOptimizationObjective>(ompl_simple_setup_->getSpaceInformation()); |
374 |
| - |
375 |
| - } |
| 364 | + objective = |
| 365 | + std::make_shared<ompl::base::PathLengthOptimizationObjective>(ompl_simple_setup_->getSpaceInformation()); |
376 | 366 |
|
377 | 367 | }
|
378 | 368 |
|
@@ -1008,3 +998,23 @@ bool ompl_interface::ModelBasedPlanningContext::loadConstraintApproximations(con
|
1008 | 998 | }
|
1009 | 999 | return false;
|
1010 | 1000 | }
|
| 1001 | + |
| 1002 | +void ompl_interface::ModelBasedPlanningContext::constructOptimizationObjectives() |
| 1003 | +{ |
| 1004 | + auto optimization_objective_loader = pluginlib::ClassLoader<ompl_optimization_loader::OptimizationObjectiveLoader>("moveit_core", "ompl_optimization_loader::OptimizationObjectiveLoader"); |
| 1005 | + |
| 1006 | + for (const auto& plugin_name : optimization_objective_loader.getDeclaredClasses()) |
| 1007 | + { |
| 1008 | + try |
| 1009 | + { |
| 1010 | + RCLCPP_DEBUG(LOGGER, "Loading optimization objective : %s", plugin_name.c_str()); |
| 1011 | + std::shared_ptr<ompl_optimization_loader::OptimizationObjectiveLoader> obj_loader = optimization_objective_loader.createSharedInstance(plugin_name); |
| 1012 | + |
| 1013 | + optimization_objectives_[plugin_name] = obj_loader; |
| 1014 | + } |
| 1015 | + catch(pluginlib::PluginlibException& ex) |
| 1016 | + { |
| 1017 | + RCLCPP_ERROR(LOGGER, "The plugin %s failed to load for some reason. Error: %s", plugin_name.c_str(), ex.what()); |
| 1018 | + } |
| 1019 | + } |
| 1020 | +} |
0 commit comments