41 static const rclcpp::Logger 
LOGGER = rclcpp::get_logger(
"test_srdf");
 
   52     MoveItSetupTest::SetUp();
 
   69     generateFiles<SRDFConfig>(
"srdf");
 
   70     std::filesystem::path srdf_path = 
output_dir_ / 
"config" / (robot_name + 
".srdf");
 
   71     ASSERT_TRUE(std::filesystem::is_regular_file(srdf_path));
 
   73     ASSERT_EQ(
srdf_xml_.LoadFile(srdf_path.c_str()), tinyxml2::XML_SUCCESS);
 
   80 unsigned int countElements(
const tinyxml2::XMLNode& parent, 
const char* child_name)
 
   82   unsigned int count = 0;
 
   83   for (
const tinyxml2::XMLElement* sub_el = parent.FirstChildElement(child_name); sub_el != 
nullptr;
 
   84        sub_el = sub_el->NextSiblingElement(child_name))
 
   93   initializeWithFanuc();
 
   99   auto root = srdf_xml_.FirstChildElement(
"robot");
 
  100   EXPECT_EQ(std::string(root->Attribute(
"name")), std::string(
"fanuc"));
 
  101   EXPECT_TRUE(root->NoChildren());
 
  106   initializeWithFanuc();
 
  110   std::string group_name = 
"manipulator";
 
  113   std::vector<std::string> joints = { 
"joint_1", 
"joint_2" };
 
  118   auto root = srdf_xml_.FirstChildElement(
"robot");
 
  119   auto group_el = root->FirstChildElement(
"group");
 
  120   ASSERT_NE(group_el, 
nullptr);
 
  121   EXPECT_EQ(std::string(group_el->Attribute(
"name")), group_name);
 
  124   joints.push_back(
"joint_3");
 
  125   joints.push_back(
"joint_4");
 
  130   root = srdf_xml_.FirstChildElement(
"robot");
 
  131   group_el = root->FirstChildElement(
"group");
 
  132   ASSERT_NE(group_el, 
nullptr);
 
  138   initializeWithFanuc();
 
  142   std::string group_name = 
"manipulator";
 
  145   std::vector<std::string> links = { 
"base_link", 
"link_1" };
 
  150   auto root = srdf_xml_.FirstChildElement(
"robot");
 
  151   auto group_el = root->FirstChildElement(
"group");
 
  152   ASSERT_NE(group_el, 
nullptr);
 
  153   EXPECT_EQ(std::string(group_el->Attribute(
"name")), group_name);
 
  156   links.push_back(
"link_2");
 
  157   links.push_back(
"link_3");
 
  162   root = srdf_xml_.FirstChildElement(
"robot");
 
  163   group_el = root->FirstChildElement(
"group");
 
  164   ASSERT_NE(group_el, 
nullptr);
 
  170   initializeWithFanuc();
 
  174   std::string group_name = 
"manipulator";
 
  177   std::vector<std::string> joints = { 
"joint_1", 
"joint_2" };
 
  182   auto root = srdf_xml_.FirstChildElement(
"robot");
 
  183   auto group_el = root->FirstChildElement(
"group");
 
  184   ASSERT_NE(group_el, 
nullptr);
 
  185   EXPECT_EQ(std::string(group_el->Attribute(
"name")), group_name);
 
  189   std::vector<std::string> links = { 
"base_link", 
"link_1" };
 
  194   root = srdf_xml_.FirstChildElement(
"robot");
 
  195   group_el = root->FirstChildElement(
"group");
 
  196   ASSERT_NE(group_el, 
nullptr);
 
  197   EXPECT_EQ(std::string(group_el->Attribute(
"name")), group_name);
 
  202 int main(
int argc, 
char** argv)
 
  204   testing::InitGoogleTest(&argc, argv);
 
  205   rclcpp::init(argc, argv);
 
  206   return RUN_ALL_TESTS();
 
std::shared_ptr< SRDFConfig > srdf_config_
 
tinyxml2::XMLDocument srdf_xml_
 
void initializeWithFanuc()
 
void generateXML(const std::string &robot_name="fanuc")
 
void initializeWithURDF(const std::filesystem::path &urdf)
 
Test environment with DataWarehouse setup and help for generating files in a temp dir.
 
moveit_setup::DataWarehousePtr config_data_
 
std::filesystem::path output_dir_
 
void setLinks(const std::string &group_name, const std::vector< std::string > &link_names)
Set the specified group's link names.
 
void setJoints(const std::string &group_name, const std::vector< std::string > &joint_names)
Set the specified group's joint names.
 
T * create(const std::string &name)
Create an item with the given name and return the pointer.
 
std::filesystem::path getSharePath(const std::string &package_name)
Return a path for the given package's share folder.
 
const rclcpp::Logger LOGGER
 
int main(int argc, char **argv)
 
unsigned int countElements(const tinyxml2::XMLNode &parent, const char *child_name)