support 'world' tag for fixed objects in URDF
This commit is contained in:
@@ -379,14 +379,25 @@ bool UrdfParser::parseLink(UrdfLink& link, TiXmlElement *config, ErrorLogger* lo
|
||||
}
|
||||
} else
|
||||
{
|
||||
logger->reportWarning("No inertial data for link, using mass=1, localinertiadiagonal = 1,1,1, identity local inertial frame");
|
||||
link.m_inertia.m_mass = 1.f;
|
||||
link.m_inertia.m_linkLocalFrame.setIdentity();
|
||||
link.m_inertia.m_ixx = 1.f;
|
||||
link.m_inertia.m_iyy = 1.f;
|
||||
link.m_inertia.m_izz= 1.f;
|
||||
|
||||
logger->reportWarning(link.m_name.c_str());
|
||||
|
||||
if ((strlen(linkName)==5) && (strncmp(linkName, "world", 5))==0)
|
||||
{
|
||||
link.m_inertia.m_mass = 0.f;
|
||||
link.m_inertia.m_linkLocalFrame.setIdentity();
|
||||
link.m_inertia.m_ixx = 0.f;
|
||||
link.m_inertia.m_iyy = 0.f;
|
||||
link.m_inertia.m_izz= 0.f;
|
||||
} else
|
||||
{
|
||||
|
||||
logger->reportWarning("No inertial data for link, using mass=1, localinertiadiagonal = 1,1,1, identity local inertial frame");
|
||||
link.m_inertia.m_mass = 1.f;
|
||||
link.m_inertia.m_linkLocalFrame.setIdentity();
|
||||
link.m_inertia.m_ixx = 1.f;
|
||||
link.m_inertia.m_iyy = 1.f;
|
||||
link.m_inertia.m_izz= 1.f;
|
||||
logger->reportWarning(link.m_name.c_str());
|
||||
}
|
||||
}
|
||||
|
||||
// Multiple Visuals (optional)
|
||||
|
||||
Reference in New Issue
Block a user