ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
2

URDF and frames of reference

asked 2014-03-14 09:44:15 -0600

Kourosh gravatar image

Hi everyone.

I sincerely apologize if my question sounds stupid or has been answered before (I searched the forum and have read the tutorials but didn't find my answer). I'm currently building a URDF file for our robot using xacro. What I've noticed is that the origin of the frame of reference of every link is in the center of that link. For example when modeling hands, the tf will point to the center of the hand. I wanted to change this so tf frames will represent joints of hands and other parts of the robot, and not the middle of link. How is that possible to do?

Btw the current robot model is:

<?xml version="1.0"?>
<robot xmlns:xacro="----KARMA INSUFFICIENT" name="my_robot">
<!-- base cylinder properties -->
<xacro:property name="cyl_radius"                           value=".5"/>
<xacro:property name="cyl_height"                           value=".3"/>
<xacro:property name="cyl_buttom"                           value=".2"/> <!-- NOTE: not used currently -->
<!-- wheel properties -->
<xacro:property name="wheel_height"                         value=".2"/>
<xacro:property name="wheel_dist_to_center"                 value=".2"/>
<!-- laserscanner properties -->
<xacro:property name="laserscanner_dist_to_center"          value=".2"/>
<xacro:property name="laserscanner_height"                  value=".2"/>
<!-- body properties -->
<xacro:property name="body_dist_to_center"                  value=".35"/>
<xacro:property name="body_height"                          value="1.5"/>
<xacro:property name="body_width"                           value="0.07"/>
<!-- shoulder cylinder properties -->
<xacro:property name="shoulder_to_body_distance_x"          value=".15"/>
<xacro:property name="shoulder_rec_size"                    value=".07"/>
<xacro:property name="shoulder_length"                      value=".5"/>
<xacro:property name="shoulder_min_height"                  value=".8"/>
<xacro:property name="shoulder_max_height"                  value=".2"/>
<xacro:property name="max_shoulder_leveler_velocity"        value=".2"/>
<xacro:property name="max_shoulder_leveler_effort"          value=".2"/>
<!-- hands properties -->
<xacro:property name="upper_arm_length"                     value=".5"/>
<xacro:property name="forearm_length"                       value=".2"/>
<xacro:property name="upper_arm_min_angle"                  value=".2"/>
<xacro:property name="upper_arm_max_angle"                  value=".2"/>
<xacro:property name="forearm_min_angle"                    value="-4"/>
<xacro:property name="forearm_max_angle"                    value="4"/>
<xacro:property name="arm_max_effort"                       value=".2"/>
<xacro:property name="arm_max_velocity"                     value=".2"/>
<!-- Starting the robot definition -->
<link name="base_link">
    <visual>
        <geometry>
            <cylinder radius="${cyl_radius}" length="${cyl_height}"/>
        </geometry>
        <material name="blue">
            <color rgba="0 0 .8 1"/>
        </material>
    </visual>
    <collision>
        <geometry>
            <cylinder radius="${cyl_radius}" length="${cyl_height}"/>
        </geometry>
        <origin xyz="0 0 0" rpy="0 0 0"/>
    </collision>
</link>

<joint name="base_to_body_joint" type="fixed">
    <parent link="base_link"/>
    <child link="body"/>
    <origin xyz="${body_dist_to_center} 0 ${(cyl_height + body_height)/2}"/>
</joint>

<link name="body">
    <visual>
        <geometry>
            <box size="${body_width} ${body_width} ${body_height}"/>
        </geometry>
        <material name="red">
            <color rgba="1 0 0 1"/>
        </material>
    </visual>
    <collision>
        <geometry>
            <box size="${body_width} ${body_width} ${body_height}"/>
        </geometry>
    </collision>
</link>

<joint name="shoulder_leveler" type="prismatic">
    <parent link="body"/>
    <child link="shoulder"/>
    <origin xyz="${shoulder_to_body_distance_x} 0 ${(shoulder_min_height + shoulder_max_height - body_height)/2}" rpy="0 0 0"/>
    <axis xyz="0 0 1"/>
    <limit lower="${shoulder_min_height}" upper="${shoulder_max_height}" 
           effort="${max_shoulder_leveler_effort}" velocity="${max_shoulder_leveler_velocity}" />
</joint>

<link name="shoulder">
    <visual>
        <geometry>
            <box size="${shoulder_rec_size} ${shoulder_length} ${shoulder_rec_size}"/>
        </geometry>
        <material name="red_1">
            <color rgba="0.5 0 0 1"/>
        </material>

    </visual>
    <collision>
        <geometry>
            <box size="${shoulder_rec_size} ${shoulder_length} ${shoulder_rec_size}"/>
        </geometry>
    </collision>
</link>


<xacro:macro name="hand" params="prefix reflect">
    <joint name="${prefix}_shoulder_joint" type="revolute">
        <parent link="shoulder"/>
        <child link="${prefix}_upper_arm"/>
        <axis xyz="0 1 0"/>
        <origin xyz="0 ${reflect * shoulder_length/2} ${-upper_arm_length/2}"/>
        <limit lower ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
5

answered 2014-03-14 18:21:08 -0600

Maya gravatar image

updated 2014-03-14 18:23:42 -0600

Ok it took me some time to figure out the solution to this problem as well.

When you're designing your robot you have different kind of things to think about.

First of all your place all of you tf frames. Tf frames are independent of the actual robot appearance. The hand frame could not be "on" the hand (but it would not be very handy though).

That's what you do when you write something like

 <joint name="${prefix}_shoulder_joint" type="revolute">
    <parent link="shoulder"/>
    <child link="${prefix}_upper_arm"/>
    <axis xyz="0 1 0"/>
    <origin xyz="0 ${reflect * shoulder_length/2} ${-upper_arm_length/2}"/>
    <limit lower="${upper_arm_min_angle}" upper="${upper_arm_max_angle}" 
            effort="${arm_max_effort}" velocity="${arm_max_velocity}" />
</joint>

There is the origin element define where your frame is going to be. You thus defined the position of each tf frame of the robot

Now you want to draw the robot itself. You have to use the visual element for that. For example

 <link name="${prefix}_upper_arm">
    <visual>
        <geometry>
            <box size="0.07 0.07 ${upper_arm_length}"/>
        </geometry>
        <material name="green">
            <color rgba="0 1 0 1"/>
        </material>
    </visual>
</link>

Here in your code you are missing an origin element like this one :

      <origin rpy="0 0 0" xyz="0 0 ${hand_length/2}"/>

This element will define the origin of the visual shape compared to the tf frame. The rpy define the rotation while the xyz define the translations. So you can just move the visual element around the tf frame to have it wherever you want.

To summarize :

First you define the tf frame place. The visual shape is going to be centered on that shape so you use the origin element to place it in space, compared to the tf frame it depend on.

Hope I have been clear enough.

edit flag offensive delete link more

Comments

Thank you very much. Everything is now much simpler because of your suggestion.

Kourosh gravatar image Kourosh  ( 2014-03-22 01:41:04 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2014-03-14 09:44:15 -0600

Seen: 4,024 times

Last updated: Mar 14 '14