37 #include <gtest/gtest.h>
44 const std::vector<std::string> REQUEST_ADAPTERS{
"planning_pipeline_test/AlwaysSuccessRequestAdapter",
45 "planning_pipeline_test/AlwaysSuccessRequestAdapter" };
46 const std::vector<std::string> RESPONSE_ADAPTERS{
"planning_pipeline_test/AlwaysSuccessResponseAdapter",
47 "planning_pipeline_test/AlwaysSuccessResponseAdapter" };
48 const std::vector<std::string> PLANNER_PLUGINS{
"planning_pipeline_test/DummyPlannerManager",
49 "planning_pipeline_test/DummyPlannerManager" };
57 node_ = rclcpp::Node::make_shared(
"planning_pipeline_test");
63 std::shared_ptr<rclcpp::Node>
node_;
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,
118 int main(
int argc,
char** argv)
120 rclcpp::init(argc, argv);
121 testing::InitGoogleTest(&argc, argv);
122 return RUN_ALL_TESTS();
std::shared_ptr< rclcpp::Node > node_
planning_pipeline::PlanningPipelinePtr pipeline_ptr_
std::shared_ptr< const moveit::core::RobotModel > robot_model_
Easily build different robot models for testing. Essentially a programmer-friendly light wrapper arou...
moveit::core::RobotModelPtr build()
Builds and returns the robot model added to the builder.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
TEST_F(TestPlanningPipeline, HappyPath)
int main(int argc, char **argv)
Response to a planning query.
moveit::core::MoveItErrorCode error_code