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

move_base_interruptable_server seems to be causing move_base to crash #87

Merged
merged 5 commits into from
Aug 8, 2017
Merged
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/GlobalPlanner/make_plan");
make_plan_client_ = nh_->serviceClient<nav_msgs::GetPlan>("move_base/NavfnROS/make_plan");
make_plan_client_.waitForExistence();
ROS_INFO_STREAM("SegbotLogicalTranslator: make_plan service found!");
make_plan_client_initialized_ = true;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@ robot_base_frame: base_footprint
update_frequency:
publish_frequency: 1.0
inflation_radius: 1.0
obstacle_layer/footprint_clearing_enabled: false

# publish_voxel_map: true
#
Expand Down
1 change: 0 additions & 1 deletion segbot_navigation/launch/move_base_eband.launch
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,6 @@
<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
3 changes: 2 additions & 1 deletion segbot_navigation/src/move_base_interruptable_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@ void newGoalCallback(const InterruptableActionServer<move_base_msgs::MoveBaseAct
ROS_INFO_STREAM("New goal received, but unable to find plan to goal. Clearing costmaps before sending goal to nav stack.");
std_srvs::Empty srv;
if (!clear_costmap_service_->call(srv)) {
// this sometimes crashes move_base
ROS_ERROR_STREAM("Unable to clear costmaps!");
} else {
// Sleep for three seconds to allow costmaps to be cleared and reset properly.
Expand All @@ -55,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/GlobalPlanner/make_plan");
*make_plan_service_ = nh.serviceClient<nav_msgs::GetPlan>("move_base/NavfnROS/make_plan");
make_plan_service_->waitForExistence();

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