Skip to content

Commit

Permalink
made changes as per comments
Browse files Browse the repository at this point in the history
  • Loading branch information
Shobuj-Paul committed Nov 1, 2023
1 parent a721379 commit 1ab8fe4
Show file tree
Hide file tree
Showing 3 changed files with 3 additions and 9 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,6 @@
#include <moveit/planning_interface/planning_interface.h>
#include <moveit_msgs/msg/motion_plan_request.hpp>
#include <moveit_msgs/msg/motion_plan_response.hpp>
#include <rclcpp/node.hpp>
#include <string>
#include <map>
#include <rclcpp/rclcpp.hpp>
Expand Down
9 changes: 2 additions & 7 deletions moveit_planners/ompl/ompl_interface/src/ompl_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -93,13 +93,8 @@ OMPLInterface::~OMPLInterface() = default;
void OMPLInterface::storePlannerData(const std::shared_ptr<std_srvs::srv::Trigger::Request>& /* unused */,
const std::shared_ptr<std_srvs::srv::Trigger::Response>& 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");
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand Down

0 comments on commit 1ab8fe4

Please sign in to comment.