Skip to content

Commit 413bbee

Browse files
committed
Loading OMPL's optimization objectives at launch in order to reduce the number of call to PluginLib
1 parent a2a8b48 commit 413bbee

File tree

2 files changed

+41
-21
lines changed

2 files changed

+41
-21
lines changed

moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/model_based_planning_context.h

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -47,6 +47,9 @@
4747
#include <ompl/base/StateStorage.h>
4848
#include <ompl/base/spaces/constraint/ConstrainedStateSpace.h>
4949

50+
#include <moveit/ompl_interface/ompl_optimization_objective_loader.h>
51+
#include <pluginlib/class_loader.hpp>
52+
5053
namespace ompl_interface
5154
{
5255
namespace ob = ompl::base;
@@ -388,6 +391,10 @@ class ModelBasedPlanningContext : public planning_interface::PlanningContext
388391
void registerTerminationCondition(const ob::PlannerTerminationCondition& ptc);
389392
void unregisterTerminationCondition();
390393

394+
/** \brief Construct the map with all the declared optimization objective plugin
395+
*/
396+
void constructOptimizationObjectives();
397+
391398
ModelBasedPlanningContextSpecification spec_;
392399

393400
moveit::core::RobotState complete_initial_robot_state_;
@@ -450,5 +457,8 @@ class ModelBasedPlanningContext : public planning_interface::PlanningContext
450457

451458
// if false parallel plan returns the first solution found
452459
bool hybridize_;
460+
461+
/// map of all the optimization objectives plugins
462+
std::map<std::string, std::shared_ptr<ompl_optimization_loader::OptimizationObjectiveLoader>> optimization_objectives_;
453463
};
454464
} // namespace ompl_interface

moveit_planners/ompl/ompl_interface/src/model_based_planning_context.cpp

Lines changed: 31 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -67,9 +67,6 @@
6767
#include "ompl/base/objectives/MaximizeMinClearanceObjective.h"
6868
#include <ompl/geometric/planners/prm/LazyPRM.h>
6969

70-
#include <moveit/ompl_interface/ompl_optimization_objective_loader.h>
71-
#include <pluginlib/class_loader.hpp>
72-
7370

7471
namespace ompl_interface
7572
{
@@ -102,6 +99,8 @@ ompl_interface::ModelBasedPlanningContext::ModelBasedPlanningContext(const std::
10299
complete_initial_robot_state_.update();
103100

104101
constraints_library_ = std::make_shared<ConstraintsLibrary>(this);
102+
103+
constructOptimizationObjectives();
105104
}
106105

107106
void ompl_interface::ModelBasedPlanningContext::configure(const rclcpp::Node::SharedPtr& node,
@@ -352,27 +351,18 @@ void ompl_interface::ModelBasedPlanningContext::useConfig()
352351
objective =
353352
std::make_shared<ompl::base::MaximizeMinClearanceObjective>(ompl_simple_setup_->getSpaceInformation());
354353
}
354+
else if (optimization_objectives_.find(optimizer) != optimization_objectives_.end())
355+
{
356+
objective =
357+
optimization_objectives_[optimizer]->getOptimizationObjective(ompl_simple_setup_->getSpaceInformation());
358+
}
355359
else
356360
{
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");
363363

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());
376366

377367
}
378368

@@ -1008,3 +998,23 @@ bool ompl_interface::ModelBasedPlanningContext::loadConstraintApproximations(con
1008998
}
1009999
return false;
10101000
}
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

Comments
 (0)