35 #include <gtest/gtest.h>
45 #include <rclcpp/rclcpp.hpp>
47 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"unittest_pilz_industrial_motion_planner");
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);
72 rm_loader_ = std::make_unique<robot_model_loader::RobotModelLoader>(
node_);
74 ASSERT_TRUE(
bool(
robot_model_)) <<
"Failed to load robot model";
77 ASSERT_TRUE(
node_->has_parameter(
"planning_plugin")) <<
"Could not find parameter 'planning_plugin'";
84 "moveit_core",
"planning_interface::PlannerManager");
86 catch (pluginlib::PluginlibException& ex)
88 RCLCPP_FATAL_STREAM(LOGGER,
"Exception while creating planning plugin loader " << ex.what());
97 <<
"Initializing the planner instance failed.";
99 catch (pluginlib::PluginlibException& ex)
101 FAIL() <<
"Could not create planner " << ex.what() <<
"\n";
115 std::unique_ptr<robot_model_loader::RobotModelLoader>
rm_loader_;
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);
135 std::set<std::string> algs_set;
136 for (
const auto& alg : algs)
138 algs_set.insert(alg);
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());
153 std::vector<std::string> algs;
154 planner_instance_->getPlanningAlgorithms(algs);
156 for (
const auto& alg : algs)
159 req.planner_id = alg;
161 EXPECT_TRUE(planner_instance_->canServiceRequest(req));
172 req.planner_id =
"NON_EXISTEND_ALGORITHM_HASH_da39a3ee5e6b4b0d3255bfef95601890afd80709";
174 EXPECT_FALSE(planner_instance_->canServiceRequest(req));
185 EXPECT_FALSE(planner_instance_->canServiceRequest(req));
194 moveit_msgs::msg::MoveItErrorCodes error_code;
195 EXPECT_EQ(
nullptr, planner_instance_->getPlanningContext(
nullptr, req, error_code));
205 moveit_msgs::msg::MoveItErrorCodes error_code;
207 req.group_name =
"manipulator";
209 std::vector<std::string> algs;
210 planner_instance_->getPlanningAlgorithms(algs);
212 for (
const auto& alg : algs)
214 req.planner_id = alg;
216 EXPECT_NE(
nullptr, planner_instance_->getPlanningContext(
nullptr, req, error_code));
225 std::string desc = planner_instance_->getDescription();
226 EXPECT_GT(desc.length(), 0u);
229 int main(
int argc,
char** argv)
231 rclcpp::init(argc, argv);
232 testing::InitGoogleTest(&argc, argv);
233 return RUN_ALL_TESTS();
planning_interface::PlannerManagerPtr planner_instance_
std::unique_ptr< pluginlib::ClassLoader< planning_interface::PlannerManager > > planner_plugin_loader_
std::string planner_plugin_name_
rclcpp::Node::SharedPtr node_
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.