42 double r{ 0 }, l{ 0 };
43 if (xml_element->QueryDoubleAttribute(
"length", &(l)) != tinyxml2::XML_SUCCESS || !(l > 0))
44 std::throw_with_nested(std::runtime_error(
"Cylinder: Missing or failed parsing attribute 'length'!"));
46 if (xml_element->QueryDoubleAttribute(
"radius", &(
r)) != tinyxml2::XML_SUCCESS || !(
r > 0))
47 std::throw_with_nested(std::runtime_error(
"Cylinder: Missing or failed parsing attribute 'radius'!"));
49 return std::make_shared<tesseract_geometry::Cylinder>(
r, l);
52 tinyxml2::XMLElement*
writeCylinder(
const std::shared_ptr<const tesseract_geometry::Cylinder>& cylinder,
53 tinyxml2::XMLDocument& doc)
55 if (cylinder ==
nullptr)
56 std::throw_with_nested(std::runtime_error(
"Cylinder is nullptr and cannot be converted to XML"));
58 xml_element->SetAttribute(
"length",
toString(cylinder->getLength()).c_str());
59 xml_element->SetAttribute(
"radius",
toString(cylinder->getRadius()).c_str());