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

Gazebo model not fixed to world, Virtual/Dummy joints

asked 2020-05-13 05:22:58 -0500

matthewmarkey gravatar image

updated 2020-05-13 05:34:16 -0500

Ubunto 16.04 Kinetic Gazebo 7.16

My custom 4DOF arm.

I have successfully gotten my model in Rviz with Moveit! working to pass motion plans to a gazebo simulated model.

The issue I am facing now is that my model is not fixed to the gazebo world, so when a motion is executed, the model typically will perform the motion, but fall over in the process.

My question is this:

What is the correct way to fix a gazebo model to an empty world? I thought I was doing the right thing by introducing a dummy link/joint for Moveit! to utilize, then I created a virtual joint (into the Moveit Setup Assistant which can be seen in my arm.srdf) and connected that dummy link to the physical world, but it doesn't seem to be working...

Any advice is greatly appreciated.

m

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2022-12-13 03:39:42 -0500

ljaniec gravatar image

I found this tutorial from Articulated Robotics really helpful for working with a manipulator arm:

You have to have a fixed link to the world, like below.

A part of the URDF (check the links for the rest):

<!-- This first link called "world" is empty -->
<link name="world"></link>


<!-- A simple fixed joint from our empty world link, to our base. -->
<!-- The base origin is offset from the world origin. -->
<joint name="base_joint" type="fixed">
    <origin xyz="1.5 1.0 0" rpy="0 0 0"/>
    <parent link="world"/>
    <child link="base_link"/>        
</joint>


<!-- base_link is a large rectangular plate. Some things to note: -->
<!-- - We set the visual origin Z to half the box height, so that the link origin sits at the bottom of the box -->
<!-- - We set the collision to be identical to the visual -->
<!-- - We specified the colour manually (but still need to enter a name) -->
<!-- - We specified all the inertial parameters manually -->
<link name="base_link">
    <visual>
        <origin xyz="0 0 0.05" rpy="0 0 0"/>
        <geometry>
            <box size="2.5 1.5 0.1" />
        </geometry>
        <material name="green">
            <color rgba="0.2 1 0.2 1"/>
        </material>
    </visual>
    <collision>
        <origin xyz="0 0 0.05" rpy="0 0 0"/>
        <geometry>
            <box size="2.5 1.5 0.1" />
        </geometry>
    </collision>
    <inertial>
        <origin xyz="0 0 0.05" rpy="0 0 0"/>
        <mass value="12" />
        <inertia ixx="2.26" ixy="0.0" ixz="0.0" iyy="6.26" iyz="0.0" izz="8.5" />
    </inertial>
</link>
edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2020-05-13 05:22:58 -0500

Seen: 584 times

Last updated: Dec 13 '22