35#include <gtest/gtest.h>
45#include <rclcpp/rclcpp.hpp>
47static 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_plugins")) <<
"Could not find parameter 'planning_plugins'";
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;
160 req.group_name =
"manipulator";
162 EXPECT_TRUE(planner_instance_->canServiceRequest(req));
169 std::vector<std::string> algs;
170 planner_instance_->getPlanningAlgorithms(algs);
172 for (
const auto& alg : algs)
175 req.planner_id = alg;
177 EXPECT_FALSE(planner_instance_->canServiceRequest(req));
184 std::vector<std::string> algs;
185 planner_instance_->getPlanningAlgorithms(algs);
187 for (
const auto& alg : algs)
190 req.planner_id = alg;
191 req.group_name =
"1234manipulator";
193 EXPECT_FALSE(planner_instance_->canServiceRequest(req));
204 req.planner_id =
"NON_EXISTEND_ALGORITHM_HASH_da39a3ee5e6b4b0d3255bfef95601890afd80709";
205 req.group_name =
"manipulator";
207 EXPECT_FALSE(planner_instance_->canServiceRequest(req));
217 req.group_name =
"manipulator";
219 EXPECT_FALSE(planner_instance_->canServiceRequest(req));
227 moveit_msgs::msg::MotionPlanRequest req;
228 moveit_msgs::msg::MoveItErrorCodes error_code;
229 EXPECT_EQ(
nullptr, planner_instance_->getPlanningContext(
nullptr, req, error_code));
238 moveit_msgs::msg::MotionPlanRequest req;
239 moveit_msgs::msg::MoveItErrorCodes error_code;
241 req.group_name =
"manipulator";
243 std::vector<std::string> algs;
244 planner_instance_->getPlanningAlgorithms(algs);
246 for (
const auto& alg : algs)
248 req.planner_id = alg;
250 EXPECT_NE(
nullptr, planner_instance_->getPlanningContext(
nullptr, req, error_code));
259 std::string desc = planner_instance_->getDescription();
260 EXPECT_GT(desc.length(), 0u);
278 return "Test_Algorithm";
281 bool loadContext(planning_interface::PlanningContextPtr& ,
const std::string& ,
282 const std::string& )
const override
291 std::make_shared<TestPlanningContextLoader>();
294 moveit_msgs::msg::MotionPlanRequest req;
295 req.planner_id =
"Test_Algorithm";
296 req.group_name =
"manipulator";
298 moveit_msgs::msg::MoveItErrorCodes error_code;
300 EXPECT_EQ(moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED, error_code.val);
305 rclcpp::init(argc, argv);
306 testing::InitGoogleTest(&argc, argv);
307 return RUN_ALL_TESTS();
planning_interface::PlannerManagerPtr planner_instance_
std::unique_ptr< pluginlib::ClassLoader< planning_interface::PlannerManager > > planner_plugin_loader_
std::vector< std::string > planner_plugin_names_
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 Plugin for Planning with Standard Robot Commands This planner is dedicated to return a instanc...
planning_interface::PlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, moveit_msgs::msg::MoveItErrorCodes &error_code) const override
Returns a PlanningContext that can be used to solve(calculate) the trajectory that corresponds to com...
bool initialize(const moveit::core::RobotModelConstPtr &model, const rclcpp::Node::SharedPtr &node, const std::string &ns) override
Initializes the planner Upon initialization this planner will look for plugins implementing pilz_indu...
void registerContextLoader(const pilz_industrial_motion_planner::PlanningContextLoaderPtr &planning_context_loader)
Register a PlanningContextLoader to be used by the CommandPlanner.
Base class for all PlanningContextLoaders. Since planning_interface::PlanningContext has a non empty ...
virtual std::string getAlgorithm() const
Return the algorithm the loader uses.
virtual bool loadContext(planning_interface::PlanningContextPtr &planning_context, const std::string &name, const std::string &group) const =0
Return the planning context.
std::shared_ptr< PlanningContextLoader > PlanningContextLoaderPtr
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.