0
$\begingroup$

Rosanswers logo

Hey there,

I want to change the base position.

image description

In this given example, I want to attach my robot upside facing towards down. I there any way to do it?

I have tried changing the urdf file, but the robot orientation and linking all joints 180 degrees was causing the problem. Any easy idea to achieve this type of result?

 <?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- |    This document was autogenerated by xacro from kr16_2.xacro                   | -->
<!-- |    EDITING THIS FILE BY HAND IS NOT RECOMMENDED                                 | -->
<!-- =================================================================================== -->
<!--Generates a urdf from the macro in kr16_2_macro.xacro -->
<robot name="kuka_kr16_2" xmlns:xacro="http://wiki.ros.org/xacro">
  <!-- LINKS -->
  <!-- base link -->
  <link name="base_link">
    <inertial>
      <origin rpy="3.14 0 0" xyz="0 0 2.35"/>
      <mass value="2"/>
      <inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
    </inertial>
    <visual>
      <origin rpy="3.14 0 0" xyz="0 0 2.35"/>
      <geometry>
        <mesh filename="package://kuka_kr16_support/meshes/kr16_2/visual/base_link.dae"/>
      </geometry>
    </visual>
    <collision>
      <origin rpy="3.14 0 0" xyz="0 0 2.35"/>
      <geometry>
        <mesh filename="package://kuka_kr16_support/meshes/kr16_2/collision/base_link.stl"/>
      </geometry>
    </collision>
  </link>
  <!-- link 1 (A1) -->
  <link name="link_1">
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <mass value="2"/>
      <inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://kuka_kr16_support/meshes/kr16_2/visual/link_1.dae"/>
      </geometry>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://kuka_kr16_support/meshes/kr16_2/collision/link_1.stl"/>
      </geometry>
    </collision>
  </link>
  <!-- link 2 -->
  <link name="link_2">
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <mass value="2"/>
      <inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://kuka_kr16_support/meshes/kr16_2/visual/link_2.dae"/>
      </geometry>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://kuka_kr16_support/meshes/kr16_2/collision/link_2.stl"/>
      </geometry>
    </collision>
  </link>
  <!-- link 3 -->
  <link name="link_3">
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <mass value="2"/>
      <inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://kuka_kr16_support/meshes/kr16_2/visual/link_3.dae"/>
      </geometry>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://kuka_kr16_support/meshes/kr16_2/collision/link_3.stl"/>
      </geometry>
    </collision>
  </link>
  <!-- link 4 -->
  <link name="link_4">
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <mass value="2"/>
      <inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://kuka_kr16_support/meshes/kr16_2/visual/link_4.dae"/>
      </geometry>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://kuka_kr16_support/meshes/kr16_2/collision/link_4.stl"/>
      </geometry>
    </collision>
  </link>
  <!-- link 5 -->
  <link name="link_5">
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <mass value="2"/>
      <inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://kuka_kr16_support/meshes/kr16_2/visual/link_5.dae"/>
      </geometry>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://kuka_kr16_support/meshes/kr16_2/collision/link_5.stl"/>
      </geometry>
    </collision>
  </link>
  <!-- link 6 -->
  <link name="link_6">
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <mass value="2"/>
      <inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://kuka_kr16_support/meshes/kr16_2/visual/link_6.dae"/>
      </geometry>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://kuka_kr16_support/meshes/kr16_2/collision/link_6.stl"/>
      </geometry>
    </collision>
  </link>
  <!-- tool 0 -->
  <!-- This frame corresponds to the $FLANGE coordinate system in KUKA KRC controllers. -->
  <link name="tool0"/>
  <!-- END LINKS -->
  <!-- JOINTS -->
  <!-- joint 1 (A1) -->
  <joint name="joint_a1" type="revolute">
    <origin rpy="3.14 0 0" xyz="0 0 1.675"/>
    <parent link="base_link"/>
    <child link="link_1"/>
    <axis xyz="0 0 1.35"/>
    <limit effort="0" lower="-3.22885911619" upper="3.22885911619" velocity="2.72271363311"/>
  </joint>
  <!-- joint 2 (A2) -->
  <joint name="joint_a2" type="revolute">
    <origin rpy="0 0 0" xyz="0.26 0 0"/>
    <parent link="link_1"/>
    <child link="link_2"/>
    <axis xyz="0 1 0"/>
    <limit effort="0" lower="-2.70526034059" upper="0.610865238198" velocity="2.72271363311"/>
  </joint>
  <!-- joint 3 (A3) -->
  <joint name="joint_a3" type="revolute">
    <origin rpy="0 0 0" xyz="0.68 0 0"/>
    <parent link="link_2"/>
    <child link="link_3"/>
    <axis xyz="0 1 0"/>
    <limit effort="0" lower="-2.26892802759" upper="2.68780704807" velocity="2.72271363311"/>
  </joint>
  <!-- joint 4 (A4) -->
  <joint name="joint_a4" type="revolute">
    <origin rpy="0 0 0" xyz="0.67 0 -0.035"/>
    <parent link="link_3"/>
    <child link="link_4"/>
    <axis xyz="-1 0 0"/>
    <limit effort="0" lower="-6.10865238198" upper="6.10865238198" velocity="5.75958653158"/>
  </joint>
  <!-- joint 5 (A5) -->
  <joint name="joint_a5" type="revolute">
    <origin rpy="0 0 0" xyz="0 0 0"/>
    <parent link="link_4"/>
    <child link="link_5"/>
    <axis xyz="0 1 0"/>
    <limit effort="0" lower="-2.26892802759" upper="2.26892802759" velocity="5.75958653158"/>
  </joint>
  <!-- joint 6 (A6) -->
  <joint name="joint_a6" type="revolute">
    <origin rpy="0 0 0" xyz="0 0 0"/>
    <parent link="link_5"/>
    <child link="link_6"/>
    <axis xyz="-1 0 0"/>
    <limit effort="0" lower="-6.10865238198" upper="6.10865238198" velocity="10.7337748998"/>
  </joint>
  <!-- tool frame - fixed frame -->
  <joint name="joint_a6-tool0" type="fixed">
    <parent link="link_6"/>
    <child link="tool0"/>
    <origin rpy="0 1.57079632679 0" xyz="0.158 0 0"/>
  </joint>
  <!-- END JOINTS -->
  <!-- ROS base_link to KUKA $ROBROOT coordinate system transform -->
  <link name="base"/>
  <joint name="base_link-base" type="fixed">
    <origin rpy="3.14 0 0" xyz="0 0 2.35"/>
    <parent link="base_link"/>
    <child link="base"/>
  </joint>
</robot>

I have just changed rpy, xyz of base_link and rpy, xyz , and child axis xyz of joint_a1

Solved but confused with the base_link. It should be Either it should be on the top near a base location?

image description

Thanks.


Originally posted by Ranjit Kathiriya on ROS Answers with karma: 1622 on 2021-02-17

Post score: 1


Original comments

Comment by fvd on 2021-02-17:
Please show how you changed the URDF file and what error you received.

Comment by gvdhoorn on 2021-02-17:
Apart from the fact you're using a KUKA, this reads like a duplicate of #q321902.

If you agree, please close your question as such.

Edit: it might be good to change the title of your question to "I want to attach my robot upside-down". The current title asks about a possible solution, which is typically regarded as an xy-problem.

Comment by gvdhoorn on 2021-02-17:
Please post updates by appending to in your original question text. Do not use comments for this.

Use the edit button/link under your original post to update it.

Comment by Ranjit Kathiriya on 2021-02-17:
I am sorry was not knowing that we can edit the original question post. I am not able to delete this comment. I am getting 10 minutes posting error.

$\endgroup$

1 Answer 1

0
$\begingroup$

Rosanswers logo

I have just changed rpy, xyz of base_link and rpy, xyz , and child axis xyz of joint_a1

It appears you've edited the existing base_link-base transform (ie: joint):

<!-- ROS base_link to KUKA $ROBROOT coordinate system transform -->
<link name="base"/>
<joint name="base_link-base" type="fixed">
  <origin rpy="3.14 0 0" xyz="0 0 2.35"/>
  <parent link="base_link"/>
  <child link="base"/>
</joint>

that's not what #q321902 suggests and I would strongly recommend not to do that.

From that Q&A:

Create a new .xacro file, import the robot macro .xacro as you'd normally do.

Then create the fixed joint that you'd normally create to place the robot in your scene, but instead of using an identity transform (ie: xyz="0 0 0" rpy="0 0 0") specify a Z-offset (to translate it "into the air"), then rotate it over either the Y or the X axis by 180 degrees and make the robot's base_link the child frame.

The important parts are:

  • create a new .xacro (so do not edit any existing files)
  • add a joint, make it of type=fixed
  • set the parent link to the name of the link you want to attach your robot model to
  • set the child link to the first link of the robot model

The "first link of the robot model" is always called base_link in the models found in ros-industrial/kuka_experimental. The base_link is in general the "start of a model" in ROS. There is nothing special about base_link (it's just another link as far as the URDF parser is concerned), but by convention (ie: an implicit agreement among users), we always start robot models with it in ROS.

In the model you're using (from ros-industrial/kuka_experimental), there is also a base link. Things can get a little confusing here, as KUKA itself also defines a Base frame. Those two are not identical however, and you'll want to make sure you are referring to the correct frame when talking to other ROS users, as they will not know what a KUKA Base frame is necessarily.

Unfortunately, there isn't a REP about frame names for industrial robots in ROS yet, but for now perhaps Coordinate Frames for (Serial Industrial) Manipulators could help shed some light on this (ignore the Vendor Nomenclature Mapping section, it's incorrect). This is not an active REP, but a document on the conventions we've used in ROS-Industrial.

Now back to your question:

Solved but confused with the base_link. It should be Either it should be on the top near a base location?

The example in #q321902 has this:

<?xml version="1.0" ?>
<robot name="upside_down_m10ia" xmlns:xacro="http://wiki.ros.org/xacro">
  <xacro:include filename="$(find fanuc_m10ia_support)/urdf/m10ia_macro.xacro"/>
>       <xacro:fanuc_m10ia prefix="robot_"/>
>     
>       <link name="world" />
>       <joint name="ceiling_joint" type="fixed">
>         <origin xyz="0 0 2" rpy="0 ${radians(180)} 0" />
    <parent link="world" />
    <child link="robot_base_link" />
  </joint>
</robot>

The idea is to consider the robot model immutable (ie: you never touch it, it's read-only), and you attach it to other geometry in your robot cell (ie: the metal frame) by adding additional joints.

You don't show us the URDF for the metal frame you show in your picture, but with the structure shown in the example here, you'd probably replace world (ie, the parent link) with the name of whatever link you have in your metal frame where the robot should be mounted.

Summarising: don't edit the base_link-base joint in the kuka_kr16_2 xacro:macro, but attach the robot model to your metal frame by using an additional joint. That will result in the base_link of the robot model to be in the right place.


Originally posted by gvdhoorn with karma: 86574 on 2021-02-17

This answer was ACCEPTED on the original site

Post score: 3


Original comments

Comment by gvdhoorn on 2021-02-17:
I would also recommend not to convert the files to URDF, but keep working with the .xacros directly. Xacro is much more flexible, as it allows to combine different xacro fragments in an easy way. URDF cannot be combined with anything else.

Comment by Ranjit Kathiriya on 2021-02-18:
Thanks for the help! and once again sorry was not knowing about the ticking. Thanks for helping me

Comment by gvdhoorn on 2021-02-18:
No need to apologise.

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.