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";
153 cartesian_limits::Params cart_limits;
154 cart_limits.max_trans_vel = 1 * M_PI;
155 cart_limits.max_trans_acc = 2;
156 cart_limits.max_trans_dec = 2;
157 cart_limits.max_rot_vel = 1;
161 planning_context_loader_->setLimits(limits);
162 planning_context_loader_->setModel(robot_model_);
166 res = planning_context_loader_->loadContext(planning_context,
"test", group_name);
168 catch (std::exception& ex)
170 FAIL() <<
"Exception!" << ex.what() <<
' ' <<
typeid(ex).name();
173 EXPECT_EQ(
true, res) <<
"Context could not be loaded!";
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_
TEST_P(PlanningContextLoadersTest, GetAlgorithm)
Test getAlgorithm returns PTP.
int main(int argc, char **argv)