@@ -84,12 +84,6 @@ PipelinePlanner::PipelinePlanner(
8484 properties ().declare <double >(" goal_position_tolerance" , 1e-4 , " tolerance for reaching position goals" );
8585 properties ().declare <double >(" goal_orientation_tolerance" , 1e-4 , " tolerance for reaching orientation goals" );
8686 // Declare properties that configure the planning pipeline
87- properties ().declare <bool >(" display_motion_plans" , false ,
88- " publish generated solutions on topic " +
89- planning_pipeline::PlanningPipeline::DISPLAY_PATH_TOPIC);
90- properties ().declare <bool >(" publish_planning_requests" , false ,
91- " publish motion planning requests on topic " +
92- planning_pipeline::PlanningPipeline::MOTION_PLAN_REQUEST_TOPIC);
9387 properties ().declare <std::unordered_map<std::string, std::string>>(
9488 " pipeline_id_planner_id_map" , std::unordered_map<std::string, std::string>(),
9589 " Set of pipelines and planners used for planning" );
@@ -143,12 +137,6 @@ void PipelinePlanner::init(const core::RobotModelConstPtr& robot_model) {
143137 throw std::runtime_error (
144138 " Cannot initialize PipelinePlanner: Could not create any valid entries for planning pipeline maps!" );
145139 }
146-
147- // Configure all pipelines according to the configuration in properties
148- for (auto const & name_pipeline_pair : planning_pipelines_) {
149- name_pipeline_pair.second ->displayComputedMotionPlans (properties ().get <bool >(" display_motion_plans" ));
150- name_pipeline_pair.second ->publishReceivedRequests (properties ().get <bool >(" publish_planning_requests" ));
151- }
152140}
153141
154142bool PipelinePlanner::plan (const planning_scene::PlanningSceneConstPtr& from,
0 commit comments