From 5b6330aa50172f58affa0a38b214f28fafd13951 Mon Sep 17 00:00:00 2001 From: Shobuj Paul Date: Mon, 30 Oct 2023 19:30:26 +0530 Subject: [PATCH] made changes as per comments --- .../include/moveit/ompl_interface/ompl_interface.h | 1 - .../ompl/ompl_interface/src/ompl_interface.cpp | 9 ++------- .../ompl/ompl_interface/src/planning_context_manager.cpp | 2 +- 3 files changed, 3 insertions(+), 9 deletions(-) diff --git a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h index 6f3d0de59f1..de76b3bf8e1 100644 --- a/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h +++ b/moveit_planners/ompl/ompl_interface/include/moveit/ompl_interface/ompl_interface.h @@ -42,7 +42,6 @@ #include #include #include -#include #include #include #include diff --git a/moveit_planners/ompl/ompl_interface/src/ompl_interface.cpp b/moveit_planners/ompl/ompl_interface/src/ompl_interface.cpp index e9865193ee6..c03787dfa60 100644 --- a/moveit_planners/ompl/ompl_interface/src/ompl_interface.cpp +++ b/moveit_planners/ompl/ompl_interface/src/ompl_interface.cpp @@ -93,13 +93,8 @@ OMPLInterface::~OMPLInterface() = default; void OMPLInterface::storePlannerData(const std::shared_ptr& /* unused */, const std::shared_ptr& response) { - bool success = context_manager_.storePlannerData(); - response->success = success; - if (success) - { - RCLCPP_INFO(LOGGER, "Stored motion planner data"); - } - else + response->success = context_manager_.storePlannerData(); + if (!response->success) { RCLCPP_ERROR(LOGGER, "Motion planning graph is empty"); } diff --git a/moveit_planners/ompl/ompl_interface/src/planning_context_manager.cpp b/moveit_planners/ompl/ompl_interface/src/planning_context_manager.cpp index b5b11fc640b..e524922d690 100644 --- a/moveit_planners/ompl/ompl_interface/src/planning_context_manager.cpp +++ b/moveit_planners/ompl/ompl_interface/src/planning_context_manager.cpp @@ -98,7 +98,7 @@ bool MultiQueryPlannerAllocator::storePlannerData() planners_[entry.first]->getPlannerData(data); if (data.numVertices() == 0) { - RCLCPP_DEBUG_STREAM(LOGGER, "Could not fetch space information or space information is empty."); + RCLCPP_ERROR_STREAM(LOGGER, "Could not fetch space information or space information is empty."); return false; } RCLCPP_INFO_STREAM(LOGGER, "Storing planner data. NumEdges: " << data.numEdges()