PipelinePlanner: disable publishing of plan request + computed path

This commit is contained in:
Robert Haschke 2018-10-19 20:49:36 +02:00
parent 36fe4c98be
commit f548b7edcc

View File

@ -93,6 +93,8 @@ Task::createPlanner(const robot_model::RobotModelConstPtr& model, const std::str
planner = std::make_shared<planning_pipeline::PlanningPipeline>
(model, ros::NodeHandle(ns), planning_plugin_param_name, adapter_plugins_param_name);
planner_cache[id] = planner;
planner->displayComputedMotionPlans(false);
planner->publishReceivedRequests(false);
}
return planner;
}