[ros-users] Urdf joints/links question
Adolfo Rodríguez Tsouroukdissian
adolfo.rodriguez at pal-robotics.com
Tue Jun 1 14:20:01 UTC 2010
On Tue, Jun 1, 2010 at 3:58 PM, Kirila Adamova <kirila.adamova at dfki.de>wrote:
> Thank you,
>
> That placed the cylinder correctly. However, I still have the rotation
> problem.
> <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.169 0 0" rpy="0 2.2 0"/>
<geometry>
> <cylinder radius="0.060" length="0.420"/>
> </geometry>
> </visual>
> <collision>
> <origin xyz="-0.169 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 1 0"/>
> <limit lower="1.31" upper="3.22" effort="30" velocity="1.0"/>
> </joint>
>
The <axis> element is specific to a joint, not a link, and specifies the
direction of motion (rotation, in your case).
If you are interested in orienting a link with respect to to a joint, then
you should use the rpy attribute of the <origin> element. For example, in
the above code, you state:
<origin xyz="-0.169 0 0" rpy="0 2.2 0"/>
Here you are specifying a pitch angle of 2.2 radians. You can choose a
suitable roll, pitch, yaw triplet that will reorient your cylinder as you
would expect.
I'm not sure if I understood your question correctly... Does this solve your
issue?
Adolfo
> If in the joint, <axis xyz="0 0 1">, the cylinder rotates around the z
> axis. When I set it to <axiz xyz="0 1 0">, it rotates around the y axis
> as I want it to, but the whole robot also jumps and rotates and falls to
> its side...
>
> Kirila
>
> Adolfo Rodríguez Tsouroukdissian wrote:
> > On Tue, Jun 1, 2010 at 3:32 PM, Kirila Adamova <kirila.adamova at dfki.de
> > <mailto:kirila.adamova at 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/Link
> > http://www.ros.org/wiki/urdf/XML/Joint
> >
> > HTH,
> >
> > 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 at code.ros.org <mailto:ros-users at code.ros.org>
> > https://code.ros.org/mailman/listinfo/ros-users
> >
> >
> >
> >
> > --
> > Adolfo Rodríguez Tsouroukdissian, Ph. D.
> >
> > Robotics engineer
> > PAL ROBOTICS S.L
> > http://www.pal-robotics.com
> > Tel. +34.93.414.53.47
> > Fax.+34.93.209.11.09
> > AVISO DE CONFIDENCIALIDAD: Este mensaje y sus documentos adjuntos,
> > pueden contener información privilegiada y/o confidencial que está
> > dirigida exclusivamente a su destinatario. Si usted recibe este
> > mensaje y no es el destinatario indicado, o el empleado encargado de
> > su entrega a dicha persona, por favor, notifíquelo inmediatamente y
> > remita el mensaje original a la dirección de correo electrónico
> > indicada. Cualquier copia, uso o distribución no autorizados de esta
> > comunicación queda estrictamente prohibida.
> >
> > CONFIDENTIALITY NOTICE: This e-mail and the accompanying document(s)
> > may contain confidential information which is privileged and intended
> > only for the individual or entity to whom they are addressed. If you
> > are not the intended recipient, you are hereby notified that any
> > disclosure, copying, distribution or use of this e-mail and/or
> > accompanying document(s) is strictly prohibited. If you have received
> > this e-mail in error, please immediately notify the sender at the
> > above e-mail address.
> > ------------------------------------------------------------------------
> >
> > _______________________________________________
> > ros-users mailing list
> > ros-users at code.ros.org
> > https://code.ros.org/mailman/listinfo/ros-users
> >
>
> _______________________________________________
> ros-users mailing list
> ros-users at code.ros.org
> https://code.ros.org/mailman/listinfo/ros-users
>
-------------- next part --------------
An HTML attachment was scrubbed...
URL: <http://lists.ros.org/pipermail/ros-users/attachments/20100601/607bb625/attachment-0003.html>
More information about the ros-users
mailing list