Memory leaks
This commit is contained in:
@@ -195,6 +195,14 @@ struct BulletMJCFImporterInternalData
|
|||||||
m_pathPrefix[0] = 0;
|
m_pathPrefix[0] = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
~BulletMJCFImporterInternalData()
|
||||||
|
{
|
||||||
|
for (int i=0;i<m_models.size();i++)
|
||||||
|
{
|
||||||
|
delete m_models[i];
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
std::string sourceFileLocation(TiXmlElement* e)
|
std::string sourceFileLocation(TiXmlElement* e)
|
||||||
{
|
{
|
||||||
#if 0
|
#if 0
|
||||||
|
|||||||
@@ -13,48 +13,10 @@ m_activeSdfModel(-1)
|
|||||||
|
|
||||||
UrdfParser::~UrdfParser()
|
UrdfParser::~UrdfParser()
|
||||||
{
|
{
|
||||||
cleanModel(&m_urdf2Model);
|
|
||||||
|
|
||||||
for (int i=0;i<m_tmpModels.size();i++)
|
for (int i=0;i<m_tmpModels.size();i++)
|
||||||
{
|
{
|
||||||
cleanModel(m_tmpModels[i]);
|
|
||||||
delete m_tmpModels[i];
|
delete m_tmpModels[i];
|
||||||
}
|
}
|
||||||
m_sdfModels.clear();
|
|
||||||
m_tmpModels.clear();
|
|
||||||
}
|
|
||||||
|
|
||||||
void UrdfParser::cleanModel(UrdfModel* model)
|
|
||||||
{
|
|
||||||
for (int i=0;i<model->m_materials.size();i++)
|
|
||||||
{
|
|
||||||
UrdfMaterial** matPtr = model->m_materials.getAtIndex(i);
|
|
||||||
if (matPtr)
|
|
||||||
{
|
|
||||||
UrdfMaterial* mat = *matPtr;
|
|
||||||
delete mat;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
for (int i=0;i<model->m_links.size();i++)
|
|
||||||
{
|
|
||||||
UrdfLink** linkPtr = model->m_links.getAtIndex(i);
|
|
||||||
if (linkPtr)
|
|
||||||
{
|
|
||||||
UrdfLink* link = *linkPtr;
|
|
||||||
delete link;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
for (int i=0;i<model->m_joints.size();i++)
|
|
||||||
{
|
|
||||||
UrdfJoint** jointPtr = model->m_joints.getAtIndex(i);
|
|
||||||
if (jointPtr)
|
|
||||||
{
|
|
||||||
UrdfJoint* joint = *jointPtr;
|
|
||||||
delete joint;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
static bool parseVector4(btVector4& vec4, const std::string& vector_str)
|
static bool parseVector4(btVector4& vec4, const std::string& vector_str)
|
||||||
@@ -1471,6 +1433,7 @@ bool UrdfParser::loadUrdf(const char* urdfText, ErrorLogger* logger, bool forceF
|
|||||||
UrdfMaterial** mat =m_urdf2Model.m_materials.find(material->m_name.c_str());
|
UrdfMaterial** mat =m_urdf2Model.m_materials.find(material->m_name.c_str());
|
||||||
if (mat)
|
if (mat)
|
||||||
{
|
{
|
||||||
|
delete material;
|
||||||
logger->reportWarning("Duplicate material");
|
logger->reportWarning("Duplicate material");
|
||||||
} else
|
} else
|
||||||
{
|
{
|
||||||
@@ -1494,6 +1457,7 @@ bool UrdfParser::loadUrdf(const char* urdfText, ErrorLogger* logger, bool forceF
|
|||||||
{
|
{
|
||||||
logger->reportError("Link name is not unique, link names in the same model have to be unique");
|
logger->reportError("Link name is not unique, link names in the same model have to be unique");
|
||||||
logger->reportError(link->m_name.c_str());
|
logger->reportError(link->m_name.c_str());
|
||||||
|
delete link;
|
||||||
return false;
|
return false;
|
||||||
} else
|
} else
|
||||||
{
|
{
|
||||||
@@ -1542,6 +1506,7 @@ bool UrdfParser::loadUrdf(const char* urdfText, ErrorLogger* logger, bool forceF
|
|||||||
{
|
{
|
||||||
logger->reportError("joint '%s' is not unique.");
|
logger->reportError("joint '%s' is not unique.");
|
||||||
logger->reportError(joint->m_name.c_str());
|
logger->reportError(joint->m_name.c_str());
|
||||||
|
delete joint;
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
@@ -1552,6 +1517,7 @@ bool UrdfParser::loadUrdf(const char* urdfText, ErrorLogger* logger, bool forceF
|
|||||||
else
|
else
|
||||||
{
|
{
|
||||||
logger->reportError("joint xml is not initialized correctly");
|
logger->reportError("joint xml is not initialized correctly");
|
||||||
|
delete joint;
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -1667,6 +1633,7 @@ bool UrdfParser::loadSDF(const char* sdfText, ErrorLogger* logger)
|
|||||||
if (mat)
|
if (mat)
|
||||||
{
|
{
|
||||||
logger->reportWarning("Duplicate material");
|
logger->reportWarning("Duplicate material");
|
||||||
|
delete material;
|
||||||
} else
|
} else
|
||||||
{
|
{
|
||||||
localModel->m_materials.insert(material->m_name.c_str(),material);
|
localModel->m_materials.insert(material->m_name.c_str(),material);
|
||||||
@@ -1689,6 +1656,7 @@ bool UrdfParser::loadSDF(const char* sdfText, ErrorLogger* logger)
|
|||||||
{
|
{
|
||||||
logger->reportError("Link name is not unique, link names in the same model have to be unique");
|
logger->reportError("Link name is not unique, link names in the same model have to be unique");
|
||||||
logger->reportError(link->m_name.c_str());
|
logger->reportError(link->m_name.c_str());
|
||||||
|
delete link;
|
||||||
return false;
|
return false;
|
||||||
} else
|
} else
|
||||||
{
|
{
|
||||||
@@ -1737,6 +1705,7 @@ bool UrdfParser::loadSDF(const char* sdfText, ErrorLogger* logger)
|
|||||||
{
|
{
|
||||||
logger->reportError("joint '%s' is not unique.");
|
logger->reportError("joint '%s' is not unique.");
|
||||||
logger->reportError(joint->m_name.c_str());
|
logger->reportError(joint->m_name.c_str());
|
||||||
|
delete joint;
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
@@ -1747,6 +1716,7 @@ bool UrdfParser::loadSDF(const char* sdfText, ErrorLogger* logger)
|
|||||||
else
|
else
|
||||||
{
|
{
|
||||||
logger->reportError("joint xml is not initialized correctly");
|
logger->reportError("joint xml is not initialized correctly");
|
||||||
|
delete joint;
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -196,6 +196,36 @@ struct UrdfModel
|
|||||||
m_rootTransformInWorld.setIdentity();
|
m_rootTransformInWorld.setIdentity();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
~UrdfModel()
|
||||||
|
{
|
||||||
|
for (int i = 0; i < m_materials.size(); i++)
|
||||||
|
{
|
||||||
|
UrdfMaterial** ptr = m_materials.getAtIndex(i);
|
||||||
|
if (ptr)
|
||||||
|
{
|
||||||
|
UrdfMaterial* t = *ptr;
|
||||||
|
delete t;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
for (int i = 0; i < m_links.size(); i++)
|
||||||
|
{
|
||||||
|
UrdfLink** ptr = m_links.getAtIndex(i);
|
||||||
|
if (ptr)
|
||||||
|
{
|
||||||
|
UrdfLink* t = *ptr;
|
||||||
|
delete t;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
for (int i = 0; i < m_joints.size(); i++)
|
||||||
|
{
|
||||||
|
UrdfJoint** ptr = m_joints.getAtIndex(i);
|
||||||
|
if (ptr)
|
||||||
|
{
|
||||||
|
UrdfJoint* t = *ptr;
|
||||||
|
delete t;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
class UrdfParser
|
class UrdfParser
|
||||||
@@ -210,7 +240,6 @@ protected:
|
|||||||
int m_activeSdfModel;
|
int m_activeSdfModel;
|
||||||
|
|
||||||
|
|
||||||
void cleanModel(UrdfModel* model);
|
|
||||||
bool parseInertia(UrdfInertia& inertia, class TiXmlElement* config, ErrorLogger* logger);
|
bool parseInertia(UrdfInertia& inertia, class TiXmlElement* config, ErrorLogger* logger);
|
||||||
bool parseGeometry(UrdfGeometry& geom, class TiXmlElement* g, ErrorLogger* logger);
|
bool parseGeometry(UrdfGeometry& geom, class TiXmlElement* g, ErrorLogger* logger);
|
||||||
bool parseVisual(UrdfModel& model, UrdfVisual& visual, class TiXmlElement* config, ErrorLogger* logger);
|
bool parseVisual(UrdfModel& model, UrdfVisual& visual, class TiXmlElement* config, ErrorLogger* logger);
|
||||||
|
|||||||
Reference in New Issue
Block a user