Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Negative cylinder mesh shapes eat up all (at least, most) of memory #64

Closed
clalancette opened this issue Jan 10, 2017 · 4 comments
Closed

Comments

@clalancette
Copy link

clalancette commented Jan 10, 2017

I'm currently looking at ros/robot_model#175 , and ran into what may be a bug. According to the URDF spec, a link with a cylinder can have a negative length and still be well-formed. For most software, this means the cylinder grows in the negative direction from the origin. However, when urdf_to_collada runs across it, it ends up down in geometric_shapes:createMeshFromShape(cylinder), where we have this code:

  double h = cylinder.length;
  ...
  unsigned int h_num = ceil(h / circle_edge);
  ...
  for (unsigned int i = 0; i < h_num - 1 ; ++i)
    for(unsigned int j = 0; j < tot; ++j)
      vertices.push_back(Eigen::Vector3d(r * cos(phi + phid * j), r * sin(phi + phid * j), h / 2 - (i + 1) * hd));

Essentially, we divide a negative length by a positive number, assign to an unsigned (now a huge positive number), and then push_back millions of items into the vector, exhausting memory. One way to fix this might be to take fabs(h) when calculating h_num, but I'm not sure if that is correct. Any advice here on how we might fix this?

@de-vri-es
Copy link
Contributor

de-vri-es commented Jan 11, 2017

It seems odd to me that the length of the cylinder affects the number of vertices. That doesn't seem necessary. Easiest fix without changing that would be to simply take the std::abs(h) when computing h_num.

I wonder if we can just remove it though, and connect the top and bottom circles directly.

@clalancette
Copy link
Author

If you think we should go with the change to std::abs, I can open a pull request for that. I'm not that familiar with this code, so I wouldn't be comfortable doing a more in-depth change to connect the top and bottom circles.

@de-vri-es
Copy link
Contributor

Understandable. A PR with std::abs would be welcome. You may also want to look at the code for converting cones to meshes, it probably has the same problem.

I suspect the extra circles may be a left-over artefact of common code (apparently adapted from FCL) for rendering cylinders and cones. But std::abs will fix the bug for now.

rhaschke added a commit to rhaschke/geometric_shapes that referenced this issue Apr 6, 2018
Computing h_num from a negative cylinder height resulted in a huge
number of vertices to be generated, eventually exhausting memory (moveit#64).
@BryceStevenWilley
Copy link
Contributor

#81 has been merged and released into kinetic and melodic, this issue should be fixed. Feel free to reopen if it's not.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

3 participants