From 481e2c83b5008b88d71ab59dc053f08886293f43 Mon Sep 17 00:00:00 2001 From: Garrett Warnell Date: Tue, 8 Aug 2017 14:30:58 -0500 Subject: [PATCH] switched back to --- .../libsegbot_logical_translator/segbot_logical_translator.cpp | 2 +- segbot_navigation/launch/move_base_eband.launch | 1 + segbot_navigation/src/move_base_interruptable_server.cpp | 2 +- 3 files changed, 3 insertions(+), 2 deletions(-) diff --git a/segbot_logical_translator/src/libsegbot_logical_translator/segbot_logical_translator.cpp b/segbot_logical_translator/src/libsegbot_logical_translator/segbot_logical_translator.cpp index c78e7ab0..35960d4a 100644 --- a/segbot_logical_translator/src/libsegbot_logical_translator/segbot_logical_translator.cpp +++ b/segbot_logical_translator/src/libsegbot_logical_translator/segbot_logical_translator.cpp @@ -167,7 +167,7 @@ namespace segbot_logical_translator { if (!make_plan_client_initialized_) { ROS_INFO_STREAM("SegbotLogicalTranslator: Waiting for make_plan service.."); - make_plan_client_ = nh_->serviceClient("move_base/NavfnROS/make_plan"); + make_plan_client_ = nh_->serviceClient("move_base/GlobalPlanner/make_plan"); make_plan_client_.waitForExistence(); ROS_INFO_STREAM("SegbotLogicalTranslator: make_plan service found!"); make_plan_client_initialized_ = true; diff --git a/segbot_navigation/launch/move_base_eband.launch b/segbot_navigation/launch/move_base_eband.launch index d97bcbf3..20786f4d 100644 --- a/segbot_navigation/launch/move_base_eband.launch +++ b/segbot_navigation/launch/move_base_eband.launch @@ -21,6 +21,7 @@ + diff --git a/segbot_navigation/src/move_base_interruptable_server.cpp b/segbot_navigation/src/move_base_interruptable_server.cpp index 2e9e9837..0b2d3b1f 100644 --- a/segbot_navigation/src/move_base_interruptable_server.cpp +++ b/segbot_navigation/src/move_base_interruptable_server.cpp @@ -56,7 +56,7 @@ int main(int argc, char *argv[]) { clear_costmap_service_->waitForExistence(); make_plan_service_.reset(new ros::ServiceClient); - *make_plan_service_ = nh.serviceClient("move_base/NavfnROS/make_plan"); + *make_plan_service_ = nh.serviceClient("move_base/GlobalPlanner/make_plan"); make_plan_service_->waitForExistence(); ROS_INFO_STREAM("move_base_interruptable : Navigation services found!");