Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

debug move_base crash when using global_planner/GlobalPlanner #91

Open
wants to merge 1 commit into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -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<nav_msgs::GetPlan>("move_base/NavfnROS/make_plan");
make_plan_client_ = nh_->serviceClient<nav_msgs::GetPlan>("move_base/GlobalPlanner/make_plan");
make_plan_client_.waitForExistence();
ROS_INFO_STREAM("SegbotLogicalTranslator: make_plan service found!");
make_plan_client_initialized_ = true;
Expand Down
1 change: 1 addition & 0 deletions segbot_navigation/launch/move_base_eband.launch
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
<rosparam file="$(find segbot_navigation)/config/$(arg config)/eband_planner_params.yaml" command="load"/>

<param name="base_local_planner" value="eband_local_planner/EBandPlannerROS" />
<param name="base_global_planner" value="global_planner/GlobalPlanner" />

<param name="global_costmap/map_topic" value="$(arg map_topic)"/>

Expand Down
2 changes: 1 addition & 1 deletion segbot_navigation/src/move_base_interruptable_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<nav_msgs::GetPlan>("move_base/NavfnROS/make_plan");
*make_plan_service_ = nh.serviceClient<nav_msgs::GetPlan>("move_base/GlobalPlanner/make_plan");
make_plan_service_->waitForExistence();

ROS_INFO_STREAM("move_base_interruptable : Navigation services found!");
Expand Down