moveit2
The MoveIt Motion Planning Framework for ROS 2.
unittest_pilz_industrial_motion_planner.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018 Pilz GmbH & Co. KG
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 Pilz GmbH & Co. KG 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 #include <gtest/gtest.h>
36 
37 #include <iostream>
38 
41 
43 #include "test_utils.h"
44 
45 #include <rclcpp/rclcpp.hpp>
46 
47 static const rclcpp::Logger LOGGER = rclcpp::get_logger("unittest_pilz_industrial_motion_planner");
48 
49 class CommandPlannerTest : public testing::Test
50 {
51 protected:
52  void SetUp() override
53  {
54  rclcpp::NodeOptions node_options;
55  node_options.automatically_declare_parameters_from_overrides(true);
56  node_ = rclcpp::Node::make_shared("unittest_pilz_industrial_motion_planner", node_options);
58  }
59 
70  {
71  // load robot model
72  rm_loader_ = std::make_unique<robot_model_loader::RobotModelLoader>(node_);
73  robot_model_ = rm_loader_->getModel();
74  ASSERT_TRUE(bool(robot_model_)) << "Failed to load robot model";
75 
76  // Load planner name from node parameters
77  ASSERT_TRUE(node_->has_parameter("planning_plugin")) << "Could not find parameter 'planning_plugin'";
78  node_->get_parameter<std::string>("planning_plugin", planner_plugin_name_);
79 
80  // Load the plugin
81  try
82  {
83  planner_plugin_loader_ = std::make_unique<pluginlib::ClassLoader<planning_interface::PlannerManager>>(
84  "moveit_core", "planning_interface::PlannerManager");
85  }
86  catch (pluginlib::PluginlibException& ex)
87  {
88  RCLCPP_FATAL_STREAM(LOGGER, "Exception while creating planning plugin loader " << ex.what());
89  FAIL();
90  }
91 
92  // Create planner
93  try
94  {
95  planner_instance_.reset(planner_plugin_loader_->createUnmanagedInstance(planner_plugin_name_));
96  ASSERT_TRUE(planner_instance_->initialize(robot_model_, node_, ""))
97  << "Initializing the planner instance failed.";
98  }
99  catch (pluginlib::PluginlibException& ex)
100  {
101  FAIL() << "Could not create planner " << ex.what() << "\n";
102  }
103  }
104 
105  void TearDown() override
106  {
107  planner_plugin_loader_->unloadLibraryForClass(planner_plugin_name_);
108  robot_model_.reset();
109  }
110 
111 protected:
112  // ros stuff
113  rclcpp::Node::SharedPtr node_;
114  moveit::core::RobotModelConstPtr robot_model_;
115  std::unique_ptr<robot_model_loader::RobotModelLoader> rm_loader_;
116 
117  std::string planner_plugin_name_;
118  std::unique_ptr<pluginlib::ClassLoader<planning_interface::PlannerManager>> planner_plugin_loader_;
119  planning_interface::PlannerManagerPtr planner_instance_;
120 };
121 
126 TEST_F(CommandPlannerTest, ObtainLoadedPlanningAlgorithms)
127 {
128  // Check for the algorithms
129  std::vector<std::string> algs;
130  planner_instance_->getPlanningAlgorithms(algs);
131  ASSERT_EQ(3u, algs.size()) << "Found more or less planning algorithms as expected! Found:"
132  << ::testing::PrintToString(algs);
133 
134  // Collect the algorithms, check for uniqueness
135  std::set<std::string> algs_set;
136  for (const auto& alg : algs)
137  {
138  algs_set.insert(alg);
139  }
140  ASSERT_EQ(algs.size(), algs_set.size()) << "There are two or more algorithms with the same name!";
141  ASSERT_TRUE(algs_set.find("LIN") != algs_set.end());
142  ASSERT_TRUE(algs_set.find("PTP") != algs_set.end());
143  ASSERT_TRUE(algs_set.find("CIRC") != algs_set.end());
144 }
145 
150 TEST_F(CommandPlannerTest, CheckValidAlgorithmsForServiceRequest)
151 {
152  // Check for the algorithms
153  std::vector<std::string> algs;
154  planner_instance_->getPlanningAlgorithms(algs);
155 
156  for (const auto& alg : algs)
157  {
159  req.planner_id = alg;
160 
161  EXPECT_TRUE(planner_instance_->canServiceRequest(req));
162  }
163 }
164 
169 TEST_F(CommandPlannerTest, CheckInvalidAlgorithmsForServiceRequest)
170 {
172  req.planner_id = "NON_EXISTEND_ALGORITHM_HASH_da39a3ee5e6b4b0d3255bfef95601890afd80709";
173 
174  EXPECT_FALSE(planner_instance_->canServiceRequest(req));
175 }
176 
180 TEST_F(CommandPlannerTest, CheckEmptyPlannerIdForServiceRequest)
181 {
183  req.planner_id = "";
184 
185  EXPECT_FALSE(planner_instance_->canServiceRequest(req));
186 }
187 
191 TEST_F(CommandPlannerTest, CheckPlanningContextRequestNull)
192 {
194  moveit_msgs::msg::MoveItErrorCodes error_code;
195  EXPECT_EQ(nullptr, planner_instance_->getPlanningContext(nullptr, req, error_code));
196 }
197 
202 TEST_F(CommandPlannerTest, CheckPlanningContextRequest)
203 {
205  moveit_msgs::msg::MoveItErrorCodes error_code;
206 
207  req.group_name = "manipulator";
208  // Check for the algorithms
209  std::vector<std::string> algs;
210  planner_instance_->getPlanningAlgorithms(algs);
211 
212  for (const auto& alg : algs)
213  {
214  req.planner_id = alg;
215 
216  EXPECT_NE(nullptr, planner_instance_->getPlanningContext(nullptr, req, error_code));
217  }
218 }
219 
223 TEST_F(CommandPlannerTest, CheckPlanningContextDescriptionNotEmptyAndStable)
224 {
225  std::string desc = planner_instance_->getDescription();
226  EXPECT_GT(desc.length(), 0u);
227 }
228 
229 int main(int argc, char** argv)
230 {
231  rclcpp::init(argc, argv);
232  testing::InitGoogleTest(&argc, argv);
233  return RUN_ALL_TESTS();
234 }
planning_interface::PlannerManagerPtr planner_instance_
std::unique_ptr< pluginlib::ClassLoader< planning_interface::PlannerManager > > planner_plugin_loader_
moveit::core::RobotModelConstPtr robot_model_
std::unique_ptr< robot_model_loader::RobotModelLoader > rm_loader_
void createPlannerInstance()
initialize the planner plugin The planner is loaded using the pluginlib. Checks that the planner was ...
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
int main(int argc, char **argv)
TEST_F(CommandPlannerTest, ObtainLoadedPlanningAlgorithms)
Test that PTP can be loaded This needs to be extended with every new planning Algorithm.