35 #include <gtest/gtest.h>
37 #include <pluginlib/class_loader.hpp>
46 #include <rclcpp/rclcpp.hpp>
48 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"unittest_planning_context_loader");
61 rclcpp::NodeOptions node_options;
62 node_options.automatically_declare_parameters_from_overrides(
true);
63 node_ = rclcpp::Node::make_shared(
"unittest_planning_context_loader", node_options);
66 rm_loader_ = std::make_unique<robot_model_loader::RobotModelLoader>(
node_);
68 ASSERT_FALSE(
robot_model_ ==
nullptr) <<
"There is no robot model!";
74 std::make_unique<pluginlib::ClassLoader<pilz_industrial_motion_planner::PlanningContextLoader>>(
75 "pilz_industrial_motion_planner",
"pilz_industrial_motion_planner::PlanningContextLoader");
77 catch (pluginlib::PluginlibException& ex)
79 RCLCPP_FATAL_STREAM(LOGGER,
"Exception while creating planning context loader " << ex.what());
88 catch (pluginlib::PluginlibException& ex)
107 std::unique_ptr<robot_model_loader::RobotModelLoader>
rm_loader_;
110 std::unique_ptr<pluginlib::ClassLoader<pilz_industrial_motion_planner::PlanningContextLoader>>
121 std::vector<std::string>{
"pilz_industrial_motion_planner/PlanningContextLoaderPTP",
"PTP" },
122 std::vector<std::string>{
"pilz_industrial_motion_planner/PlanningContextLoaderLIN",
"LIN" },
123 std::vector<std::string>{
"pilz_industrial_motion_planner/PlanningContextLoaderCIRC",
"CIRC" }
131 std::string alg = planning_context_loader_->getAlgorithm();
132 EXPECT_EQ(alg, GetParam().back());
140 planning_interface::PlanningContextPtr planning_context;
141 const std::string& group_name =
"manipulator";
144 bool res = planning_context_loader_->loadContext(planning_context,
"test", group_name);
145 EXPECT_EQ(
false, res) <<
"Context returned even when no limits where set";
159 planning_context_loader_->setLimits(limits);
160 planning_context_loader_->setModel(robot_model_);
164 res = planning_context_loader_->loadContext(planning_context,
"test", group_name);
166 catch (std::exception& ex)
168 FAIL() <<
"Exception!" << ex.what() <<
" " <<
typeid(ex).
name();
171 EXPECT_EQ(
true, res) <<
"Context could not be loaded!";
174 int main(
int argc,
char** argv)
176 rclcpp::init(argc, argv);
177 testing::InitGoogleTest(&argc, argv);
178 return RUN_ALL_TESTS();
std::unique_ptr< pluginlib::ClassLoader< pilz_industrial_motion_planner::PlanningContextLoader > > planning_context_loader_class_loader_
std::unique_ptr< robot_model_loader::RobotModelLoader > rm_loader_
pilz_industrial_motion_planner::PlanningContextLoaderPtr planning_context_loader_
void SetUp() override
To initialize the planning context loader The planning context loader is loaded using the pluginlib....
moveit::core::RobotModelConstPtr robot_model_
rclcpp::Node::SharedPtr node_
Set of cartesian limits, has values for velocity, acceleration and deceleration of both the translati...
void setMaxRotationalVelocity(double max_rot_vel)
Set the maximum rotational velocity.
void setMaxTranslationalVelocity(double max_trans_vel)
Set the maximal translational velocity.
void setMaxTranslationalAcceleration(double max_trans_acc)
Set the maximum translational acceleration.
void setMaxTranslationalDeceleration(double max_trans_dec)
Set the maximum translational deceleration.
Container for JointLimits, essentially a map with convenience functions. Adds the ability to as for l...
This class combines CartesianLimit and JointLimits into on single class.
void setCartesianLimits(CartesianLimit &cartesian_limit)
Set cartesian limits.
void setJointLimits(JointLimitsContainer &joint_limits)
Set joint limits.
std::shared_ptr< PlanningContextLoader > PlanningContextLoaderPtr
pilz_industrial_motion_planner::JointLimitsContainer createFakeLimits(const std::vector< std::string > &joint_names)
Create limits for tests to avoid the need to get the limits from the node parameter.
TEST_P(PlanningContextLoadersTest, GetAlgorithm)
Test getAlgorithm returns PTP.
int main(int argc, char **argv)
INSTANTIATE_TEST_SUITE_P(InstantiationName, PlanningContextLoadersTest, ::testing::Values(std::vector< std::string >{ "pilz_industrial_motion_planner/PlanningContextLoaderPTP", "PTP" }, std::vector< std::string >{ "pilz_industrial_motion_planner/PlanningContextLoaderLIN", "LIN" }, std::vector< std::string >{ "pilz_industrial_motion_planner/PlanningContextLoaderCIRC", "CIRC" }))