when visual, inertial or collision is specified but fails to parse, the parser should fail

This commit is contained in:
wim 2009-11-19 00:43:50 +00:00
parent b5c98fddfd
commit b5936c14af
3 changed files with 3389 additions and 9 deletions

View File

@ -67,8 +67,11 @@ boost::shared_ptr<Geometry> parseGeometry(TiXmlElement *g)
return geom;
}
if (!geom->initXml(shape))
return geom;
// clear geom object when fails to initialize
if (!geom->initXml(shape)){
ROS_ERROR("Geometry failed to parse");
geom.reset();
}
return geom;
}
@ -365,7 +368,7 @@ bool Link::initXml(TiXmlElement* config)
}
name = std::string(name_char);
// Inertial
// Inertial (optional)
TiXmlElement *i = config->FirstChildElement("inertial");
if (i)
{
@ -373,11 +376,11 @@ bool Link::initXml(TiXmlElement* config)
if (!inertial->initXml(i))
{
ROS_ERROR("Could not parse inertial element for Link '%s'", this->name.c_str());
inertial.reset();
return false;
}
}
// Visual
// Visual (optional)
TiXmlElement *v = config->FirstChildElement("visual");
if (v)
{
@ -385,11 +388,11 @@ bool Link::initXml(TiXmlElement* config)
if (!visual->initXml(v))
{
ROS_ERROR("Could not parse visual element for Link '%s'", this->name.c_str());
visual.reset();
return false;
}
}
// Collision
// Collision (optional)
TiXmlElement *col = config->FirstChildElement("collision");
if (col)
{
@ -397,7 +400,7 @@ bool Link::initXml(TiXmlElement* config)
if (!collision->initXml(col))
{
ROS_ERROR("Could not parse collision element for Link '%s'", this->name.c_str());
collision.reset();
return false;
}
}

File diff suppressed because it is too large Load Diff

View File

@ -1,3 +1,3 @@
<launch>
<test test-name="robot_model_parser_test" pkg="urdf" type="test_parser" args="$(find urdf)/test/pr2_desc_double_joint.xml $(find urdf)/test/pr2_desc_loop.xml $(find urdf)/test/pr2_desc_no_joint.xml $(find urdf)/test/pr2_desc_two_trees.xml $(find urdf)/test/pr2_desc_bracket.xml $(find urdf)/test/pr2_desc_double.xml $(find urdf)/test/pr2_desc_no_joint2.xml $(find urdf)/test/pr2_desc_parent_itself.xml $(find urdf)/test/pr2_desc.xml" />
<test test-name="robot_model_parser_test" pkg="urdf" type="test_parser" args="$(find urdf)/test/pr2_desc_double_joint.xml $(find urdf)/test/pr2_desc_loop.xml $(find urdf)/test/pr2_desc_no_joint.xml $(find urdf)/test/pr2_desc_two_trees.xml $(find urdf)/test/pr2_desc_bracket.xml $(find urdf)/test/pr2_desc_double.xml $(find urdf)/test/pr2_desc_no_joint2.xml $(find urdf)/test/pr2_desc_parent_itself.xml $(find urdf)/test/pr2_desc_no_filename_in_mesh.xml $(find urdf)/test/pr2_desc.xml" />
</launch>