moveit2
The MoveIt Motion Planning Framework for ROS 2.
planning_pipeline_tests.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2023, PickNik Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of PickNik Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Sebastian Jahr */
36 
37 #include <gtest/gtest.h>
38 
41 
42 namespace
43 {
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" };
50 } // namespace
51 class TestPlanningPipeline : public testing::Test
52 {
53 protected:
54  void SetUp() override
55  {
56  robot_model_ = moveit::core::RobotModelBuilder("empty_robot", "base_link").build();
57  node_ = rclcpp::Node::make_shared("planning_pipeline_test");
58  };
59  void TearDown() override
60  {
61  }
62 
63  std::shared_ptr<rclcpp::Node> node_;
64  std::shared_ptr<const moveit::core::RobotModel> robot_model_;
65  planning_pipeline::PlanningPipelinePtr pipeline_ptr_{ nullptr };
66 };
67 
69 {
70  // GIVEN a valid configuration
71  // WHEN the planning pipeline is configured
72  // THEN it is successful
73  EXPECT_NO_THROW(pipeline_ptr_ = std::make_shared<planning_pipeline::PlanningPipeline>(
74  robot_model_, node_, "", PLANNER_PLUGINS, REQUEST_ADAPTERS, RESPONSE_ADAPTERS));
75  // THEN a planning pipeline exists
76  EXPECT_NE(pipeline_ptr_, nullptr);
77  // THEN the pipeline is inactive
78  EXPECT_FALSE(pipeline_ptr_->isActive());
79  // THEN the pipeline contains a valid robot model
80  EXPECT_NE(pipeline_ptr_->getRobotModel(), nullptr);
81  // THEN the loaded request adapter names equal the adapter names input vector
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()));
84  // THEN the loaded request adapter names equal the adapter names input vector
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()));
87  // THEN the loaded planner plugin name equals the planner name input argument
88  const auto loaded_planners = pipeline_ptr_->getPlannerPluginNames();
89  EXPECT_TRUE(std::equal(loaded_planners.begin(), loaded_planners.end(), PLANNER_PLUGINS.begin()));
90 
91  // WHEN generatePlan is called
92  // THEN A successful response is created
93  planning_interface::MotionPlanResponse motion_plan_response;
94  planning_interface::MotionPlanRequest motion_plan_request;
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));
97  EXPECT_TRUE(motion_plan_response.error_code);
98 }
99 
100 TEST_F(TestPlanningPipeline, NoPlannerPluginConfigured)
101 {
102  // GIVEN a configuration without planner plugin
103  // WHEN the pipeline is configured
104  // THEN an exception is thrown
105  EXPECT_THROW(pipeline_ptr_ = std::make_shared<planning_pipeline::PlanningPipeline>(
106  robot_model_, node_, "", std::vector<std::string>(), REQUEST_ADAPTERS, RESPONSE_ADAPTERS),
107  std::runtime_error);
108 
109  // GIVEN a configuration with planner plugin called UNKNOWN
110  // WHEN the pipeline is configured
111  // THEN an exception is thrown
112  EXPECT_THROW(pipeline_ptr_ = std::make_shared<planning_pipeline::PlanningPipeline>(
113  robot_model_, node_, "", std::vector<std::string>({ "UNKNOWN" }), REQUEST_ADAPTERS,
114  RESPONSE_ADAPTERS),
115  std::runtime_error);
116 }
117 
118 int main(int argc, char** argv)
119 {
120  rclcpp::init(argc, argv);
121  testing::InitGoogleTest(&argc, argv);
122  return RUN_ALL_TESTS();
123 }
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)
moveit::core::MoveItErrorCode error_code