On Tue, Jun 1, 2010 at 3:32 PM, Kirila Adamova
<kirila.adamova@dfki.de> wrote:
Hi all,
I am currently writing a 3D model in urdf. I have two cylinders, which
are connected with a joint. The second cylinder, however, is rotated and
can be rotated further in the same direction. When I visualize them in
gazebo, the joint is in the center of the second cylinder. Is there a
way to make it at the end of the cylinder because that is the point
around which I need to rotate it. To make it more clear (or even more
confusing), here is sample code:
<link name="feet">
<inertial>
<origin xyz="0 0 0.275" rpy="0 0 0"/>
<mass value="100"/>
<inertia ixx="1" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder radius="0.100" length="0.250"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder radius="0.100" length="0.230"/>
</geometry>
</collision>
</link>
<link name="hips">
<inertial>
<origin xyz="0 0 0.570" rpy="0 2.2 0"/>
<mass value="50"/>
<inertia ixx="1" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 2.2 0"/>
<geometry>
<cylinder radius="0.060" length="0.420"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 2.2 0"/>
<geometry>
<cylinder radius="0.060" length="0.400"/>
</geometry>
</collision>
</link>
<joint name="knees" type="revolute">
<parent link="feet"/>
<child link="hips"/>
<origin xyz="0 0 0.275"/>
<axis xyz="0 0 1"/>
<limit lower="1.31" upper="3.22" effort="30" velocity="1.0"/>
</joint>
Currently, the axis xyz is set to z, although it needs to be y, because
when it's set somewhere else, the whole model goes crazy (jumps and
turns around) in gazebo.
Kirila,
The cylinder primitive makes its center coincide
with the corresponding origin (visualization, collision) and is aligned with the z axis. For your robot, it should suffice to specify an appropriate origin for your visualization and
collision geometries (with respect to the joint origin). For more details refer to the available documentation:
http://www.ros.org/wiki/urdf/XML/Linkhttp://www.ros.org/wiki/urdf/XML/JointHTH,
Adolfo
Help will be greatly appreciated,
Kirila
p.s. End result must rotate the second cylinder around the point between
the two cylinders around the y axis.
_______________________________________________
ros-users mailing list
ros-users@code.ros.org
https://code.ros.org/mailman/listinfo/ros-users