Skip to content

Commit

Permalink
Merge pull request #606 from dartsim/fix_memory_alignment
Browse files Browse the repository at this point in the history
Fix memory alignment in loading meshes
  • Loading branch information
jslee02 committed Feb 13, 2016
2 parents 8bc2e3a + e4b8aa2 commit 388b847
Show file tree
Hide file tree
Showing 8 changed files with 9,002 additions and 2 deletions.
2 changes: 1 addition & 1 deletion dart/utils/SkelParser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -869,7 +869,7 @@ dynamics::ShapePtr SkelParser::readShape(
const aiScene* model = dynamics::MeshShape::loadMesh(meshUri, _retriever);
if (model)
{
newShape = std::make_shared<dynamics::MeshShape>(
newShape = Eigen::make_aligned_shared<dynamics::MeshShape>(
scale, model, meshUri, _retriever);
}
else
Expand Down
2 changes: 1 addition & 1 deletion dart/utils/sdf/SdfParser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -646,7 +646,7 @@ dynamics::ShapePtr SdfParser::readShape(
const aiScene* model = dynamics::MeshShape::loadMesh(meshUri, _retriever);

if (model)
newShape = std::make_shared<dynamics::MeshShape>(
newShape = Eigen::make_aligned_shared<dynamics::MeshShape>(
scale, model, meshUri, _retriever);
else
{
Expand Down
41 changes: 41 additions & 0 deletions data/sdf/test/mesh.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
<sdf version='1.4'>
<model name='mesh_skeleton'>
<link name='pelvis'>
<pose>0 0 0 0 -0 0</pose>
<inertial>
<pose>0.0111 0 0.0271 0 -0 0</pose>
<mass>17.882</mass>
<inertia>
<ixx>0.1244</ixx>
<ixy>0.0008</ixy>
<ixz>-0.0007</ixz>
<iyy>0.0958</iyy>
<iyz>-0.0005</iyz>
<izz>0.1167</izz>
</inertia>
</inertial>
<collision name='pelvis_collision'>
<pose>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>pelvis.stl</uri>
</mesh>
</geometry>
</collision>
<visual name='pelvis_visual'>
<pose>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>pelvis.dae</uri>
</mesh>
</geometry>
</visual>
<velocity_decay>
<linear>0</linear>
<angular>0</angular>
</velocity_decay>
</link>
</model>
</sdf>
Loading

0 comments on commit 388b847

Please sign in to comment.