From 5eb2c6331d48c26bcf2c0b102134ea92d2a31a67 Mon Sep 17 00:00:00 2001 From: Shobuj Paul Date: Fri, 15 Sep 2023 17:22:35 +0530 Subject: [PATCH] Replaced std::bind with lambdas --- .../ompl_interface/src/ompl_interface.cpp | 29 +++++++++++++++++-- 1 file changed, 27 insertions(+), 2 deletions(-) diff --git a/moveit_planners/ompl/ompl_interface/src/ompl_interface.cpp b/moveit_planners/ompl/ompl_interface/src/ompl_interface.cpp index 90c2f073f18..1cc074066af 100644 --- a/moveit_planners/ompl/ompl_interface/src/ompl_interface.cpp +++ b/moveit_planners/ompl/ompl_interface/src/ompl_interface.cpp @@ -39,6 +39,7 @@ #include #include #include +#include namespace ompl_interface { @@ -59,7 +60,19 @@ OMPLInterface::OMPLInterface(const moveit::core::RobotModelConstPtr& robot_model store_planner_data_service_ = node_->create_service( "store_planner_data", - std::bind(&OMPLInterface::storePlannerData, this, std::placeholders::_1, std::placeholders::_2)); + [this](const std::shared_ptr, + std::shared_ptr response) -> void { + bool success = context_manager_.storePlannerData(); + response->success = success; + if (success) + { + RCLCPP_INFO(LOGGER, "Stored motion planner data"); + } + else + { + RCLCPP_ERROR(LOGGER, "Motion planning graph is empty"); + } + }); } OMPLInterface::OMPLInterface(const moveit::core::RobotModelConstPtr& robot_model, @@ -78,7 +91,19 @@ OMPLInterface::OMPLInterface(const moveit::core::RobotModelConstPtr& robot_model store_planner_data_service_ = node_->create_service( "store_planner_data", - std::bind(&OMPLInterface::storePlannerData, this, std::placeholders::_1, std::placeholders::_2)); + [this](const std::shared_ptr, + std::shared_ptr response) -> void { + bool success = context_manager_.storePlannerData(); + response->success = success; + if (success) + { + RCLCPP_INFO(LOGGER, "Stored motion planner data"); + } + else + { + RCLCPP_ERROR(LOGGER, "Motion planning graph is empty"); + } + }); } OMPLInterface::~OMPLInterface() = default;