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

a small radius cylinder looks bad #92

Conversation

eisoku9618
Copy link
Contributor

@eisoku9618 eisoku9618 commented Dec 9, 2018

I've found that if I set a cylinder radius N[cm] in URDF and convert the URDF to COLLADA with urdf_to_collada of collada_urdf, the output cylinder in COLLADA will be Nth regular prism.

So the appearance of small radius cylinder (e.g. 0.2cm) is not good.

This behavior is originally reported in ros/collada_urdf#20, and this PR will fix the problem.

A small example is below.

<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="test" >
  <link name="test_link_1cm">
    <visual>
      <geometry>
        <cylinder length="0.1" radius="0.01"/>
      </geometry>
    </visual>
  </link>

  <joint name="test_joint_1" type="fixed">
    <parent link="test_link_1cm"/>
    <child link = "test_link_2cm"/>
    <origin xyz="0.1 0 0" rpy="0 0 0"/>
  </joint>
  <link name="test_link_2cm">
    <visual>
      <geometry>
        <cylinder length="0.1" radius="0.02"/>
      </geometry>
    </visual>
  </link>

  <joint name="test_joint_2" type="fixed">
    <parent link="test_link_2cm"/>
    <child link = "test_link_3cm"/>
    <origin xyz="0.1 0 0" rpy="0 0 0"/>
  </joint>
  <link name="test_link_3cm">
    <visual>
      <geometry>
        <cylinder length="0.1" radius="0.03"/>
      </geometry>
    </visual>
  </link>

  <joint name="test_joint_3" type="fixed">
    <parent link="test_link_3cm"/>
    <child link = "test_link_4cm"/>
    <origin xyz="0.1 0 0" rpy="0 0 0"/>
  </joint>
  <link name="test_link_4cm">
    <visual>
      <geometry>
        <cylinder length="0.1" radius="0.04"/>
      </geometry>
    </visual>
  </link>

  <joint name="test_joint_4" type="fixed">
    <parent link="test_link_4cm"/>
    <child link = "test_link_5cm"/>
    <origin xyz="0.1 0 0" rpy="0 0 0"/>
  </joint>
  <link name="test_link_5cm">
    <visual>
      <geometry>
        <cylinder length="0.1" radius="0.05"/>
      </geometry>
    </visual>
  </link>
</robot>
rosrun collada_urdf urdf_to_collada test.urdf test.dae
roslaunch urdf_tutorial display.launch model:=test.dae

image

@rhaschke rhaschke merged commit 8f5d092 into moveit:melodic-devel Dec 9, 2018
rhaschke pushed a commit to rhaschke/geometric_shapes that referenced this pull request Dec 9, 2018
@eisoku9618 eisoku9618 deleted the add_minimum_number_of_triangles_for_cylinder branch December 9, 2018 10:44
@eisoku9618
Copy link
Contributor Author

I would like to use this new feature(?) in the older ros distros (e.g. indigo, jade, kinetic, lunar).
Could you backport this commit?

@rhaschke
Copy link
Contributor

rhaschke commented Dec 9, 2018

I backported to Kinetic. For older distros we don't release anymore.

@eisoku9618
Copy link
Contributor Author

OK, thank you for your time.

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

Successfully merging this pull request may close these issues.

None yet

2 participants