Skip to content

Commit a183bc1

Browse files
committed
planning_context_manager: rename protected methods
the trailing 1 and 2 and bind() usage made this harder to parse than it has to be. Technically this breaks API (the methods are protected, not private). But if you are that far into the code base to inherit here and rely on the names of these simple methods, you probably agree that this improves readability.
1 parent ddb68b6 commit a183bc1

2 files changed

Lines changed: 10 additions & 11 deletions

File tree

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

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -221,10 +221,9 @@ class PlanningContextManager
221221
const StateSpaceFactoryTypeSelector& factory_selector,
222222
const moveit_msgs::MotionPlanRequest& req) const;
223223

224-
const ModelBasedStateSpaceFactoryPtr& getStateSpaceFactory1(const std::string& group_name,
225-
const std::string& factory_type) const;
226-
const ModelBasedStateSpaceFactoryPtr& getStateSpaceFactory2(const std::string& group_name,
227-
const moveit_msgs::MotionPlanRequest& req) const;
224+
const ModelBasedStateSpaceFactoryPtr& getStateSpaceFactory(const std::string& factory_type) const;
225+
const ModelBasedStateSpaceFactoryPtr& getStateSpaceFactory(const std::string& group_name,
226+
const moveit_msgs::MotionPlanRequest& req) const;
228227

229228
/** \brief The kinematic model for which motion plans are computed */
230229
moveit::core::RobotModelConstPtr robot_model_;

moveit_planners/ompl/ompl_interface/src/planning_context_manager.cpp

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -368,8 +368,7 @@ ompl_interface::ModelBasedPlanningContextPtr ompl_interface::PlanningContextMana
368368
}
369369

370370
const ompl_interface::ModelBasedStateSpaceFactoryPtr&
371-
ompl_interface::PlanningContextManager::getStateSpaceFactory1(const std::string& /* dummy */,
372-
const std::string& factory_type) const
371+
ompl_interface::PlanningContextManager::getStateSpaceFactory(const std::string& factory_type) const
373372
{
374373
auto f = factory_type.empty() ? state_space_factories_.begin() : state_space_factories_.find(factory_type);
375374
if (f != state_space_factories_.end())
@@ -383,8 +382,8 @@ ompl_interface::PlanningContextManager::getStateSpaceFactory1(const std::string&
383382
}
384383

385384
const ompl_interface::ModelBasedStateSpaceFactoryPtr&
386-
ompl_interface::PlanningContextManager::getStateSpaceFactory2(const std::string& group,
387-
const moveit_msgs::MotionPlanRequest& req) const
385+
ompl_interface::PlanningContextManager::getStateSpaceFactory(const std::string& group,
386+
const moveit_msgs::MotionPlanRequest& req) const
388387
{
389388
// find the problem representation to use
390389
auto best = state_space_factories_.end();
@@ -466,10 +465,11 @@ ompl_interface::ModelBasedPlanningContextPtr ompl_interface::PlanningContextMana
466465
auto it = pc->second.config.find("enforce_joint_model_state_space");
467466

468467
if (it != pc->second.config.end() && boost::lexical_cast<bool>(it->second))
469-
factory_selector = std::bind(&PlanningContextManager::getStateSpaceFactory1, this, std::placeholders::_1,
470-
JointModelStateSpace::PARAMETERIZATION_TYPE);
468+
factory_selector = [this](const std::string&) {
469+
return getStateSpaceFactory(JointModelStateSpace::PARAMETERIZATION_TYPE);
470+
};
471471
else
472-
factory_selector = std::bind(&PlanningContextManager::getStateSpaceFactory2, this, std::placeholders::_1, req);
472+
factory_selector = [this, &req](const std::string& group) { return getStateSpaceFactory(group, req); };
473473

474474
ModelBasedPlanningContextPtr context = getPlanningContext(pc->second, factory_selector, req);
475475

0 commit comments

Comments
 (0)