73 EXPECT_NO_THROW(pipeline_ptr_ = std::make_shared<planning_pipeline::PlanningPipeline>(
74 robot_model_, node_,
"", PLANNER_PLUGINS, REQUEST_ADAPTERS, RESPONSE_ADAPTERS));
76 EXPECT_NE(pipeline_ptr_,
nullptr);
78 EXPECT_FALSE(pipeline_ptr_->isActive());
80 EXPECT_NE(pipeline_ptr_->getRobotModel(),
nullptr);
82 const auto loaded_req_adapters = pipeline_ptr_->getRequestAdapterPluginNames();
83 EXPECT_TRUE(std::equal(loaded_req_adapters.begin(), loaded_req_adapters.end(), REQUEST_ADAPTERS.begin()));
85 const auto loaded_res_adapters = pipeline_ptr_->getResponseAdapterPluginNames();
86 EXPECT_TRUE(std::equal(loaded_res_adapters.begin(), loaded_res_adapters.end(), RESPONSE_ADAPTERS.begin()));
88 const auto loaded_planners = pipeline_ptr_->getPlannerPluginNames();
89 EXPECT_TRUE(std::equal(loaded_planners.begin(), loaded_planners.end(), PLANNER_PLUGINS.begin()));
95 const auto planning_scene_ptr = std::make_shared<planning_scene::PlanningScene>(robot_model_);
96 EXPECT_TRUE(pipeline_ptr_->generatePlan(planning_scene_ptr, motion_plan_request, motion_plan_response));
105 EXPECT_THROW(pipeline_ptr_ = std::make_shared<planning_pipeline::PlanningPipeline>(
106 robot_model_, node_,
"", std::vector<std::string>(), REQUEST_ADAPTERS, RESPONSE_ADAPTERS),
112 EXPECT_THROW(pipeline_ptr_ = std::make_shared<planning_pipeline::PlanningPipeline>(
113 robot_model_, node_,
"", std::vector<std::string>({
"UNKNOWN" }), REQUEST_ADAPTERS,