Gazebo | Ignition | Community
Ask Your Question
0

Gazebo object spawned in robot link frame does not move with robot link

asked 2016-07-30 18:02:49 -0600

jwatson_utah_edu gravatar image

ROS Indigo on Ubuntu 14.04 with Gazebo 7.3 and Python 2.7

I use a Gazebo service to spawn a fixed object in a link reference frame, but the object remains fixed with respect to the world instead of with respect to the frame. Why is this so? Here is the rospy code:

def test_robot_attachment():
    """ Try attaching an axes model to a robot frame and see what happens """
    global attachCounter
    spawn_model_prox = rospy.ServiceProxy('gazebo/spawn_sdf_model', SpawnModel) # Get a handle to the Gazebo model spawner
    modelPath = rospack.get_path('grasp_anything') + '/urdf/block_axes.urdf' # Build a path to the model URDF
    f = open(modelPath,'r') # Open the URDF for reading
    sdff = f.read() # and read it
    rospy.wait_for_service('gazebo/spawn_sdf_model') # Wait for the model loader to be ready
    targetPose = ROS_geo_pose_from_lists( [ 0.5 , 0.5 , 0.5 ] , [0,0,0,1] )
    spawn_model_prox("axesAttached" + str(attachCounter), sdff, "robotos_name_space", targetPose, "lbr4_allegro::lbr4_7_link") # gen model name and place the axes at the specfied pose
    attachCounter += 1

Is there a way to attach a model to a moving frame such that it moves with the frame but is static within the frame itself? As you can see below, the URDF being inserted has no collision geometry, the model is set to static, and gravity is turned off for the model.

Here is "block_axes.urdf":

<?xml version="1.0"?>
<!-- URL, Spawning simple geometry in Gazebo: http://wiki.ros.org/simulator_gazebo/Tutorials/SpawningObjectInSimulation -->
<robot name="block_axes"> <!-- Every URDF model you add is a "robot" -->
    <link name="x_axis">
        <!-- URL, Inertia element must be present: http://gazebosim.org/tutorials?tut=ros_urdf#%3Cinertial%3EElement -->
        <inertial>
            <origin xyz="2 0 0" />
            <mass value="1.0" />
            <inertia  ixx="1.0" ixy="0.0"  ixz="0.0"  iyy="100.0"  iyz="0.0"  izz="1.0" />
        </inertial>
        <visual>
            <!--origin xyz="2 0 1"/-->  <!-- Is this absolute or relative? -->
            <origin xyz="0.05 0 0"/>
            <geometry>
                <box size="0.1 0.01 0.01" />
            </geometry>
        </visual>
    </link>
    <joint name="X-Y" type="continuous">
        <parent link="x_axis"/>
        <child  link="y_axis"/>
    </joint>
    <link name="y_axis">
        <!-- URL, Inertia element must be present: http://gazebosim.org/tutorials?tut=ros_urdf#%3Cinertial%3EElement -->
        <inertial>
            <origin xyz="2 0 0" />
            <mass value="1.0" />
            <inertia  ixx="1.0" ixy="0.0"  ixz="0.0"  iyy="100.0"  iyz="0.0"  izz="1.0" />
        </inertial>
        <visual>
            <!--origin xyz="2 0 1"/-->  <!-- Is this absolute or relative? -->
            <origin xyz="0 0.05 0"/>
            <geometry>
                <box size="0.01 0.1 0.01" />
            </geometry>
        </visual>
    </link>
    <joint name="X-Z" type="continuous">
        <parent link="x_axis"/>
        <child  link="z_axis"/>
    </joint>
    <link name="z_axis">
        <!-- URL, Inertia element must be present: http://gazebosim.org/tutorials?tut=ros_urdf#%3Cinertial%3EElement -->
        <inertial>
            <origin xyz="2 0 0" />
            <mass value="1.0" />
            <inertia  ixx="1.0" ixy="0.0"  ixz="0.0"  iyy="100.0"  iyz="0.0"  izz="1.0" />
        </inertial>
        <visual>
            <!--origin xyz="2 0 1"/-->  <!-- Is this absolute or relative? -->
            <origin xyz="0 0 0.05"/>
            <geometry>
                <box size="0.01 0.01 0.1" />
            </geometry>
        </visual>
    </link>
    <gazebo reference ...
(more)
edit retag flag offensive close merge delete

Comments

My present goal is to attach and detach a physics object to and from a particular robot link. I need something even "cheaper" than the `gazebo_grasp_plugin`, as I wish to avoid all contact modeling, and `gazebo_grasp_plugin`, does not allow joints in between palm and gripper tips.

jwatson_utah_edu gravatar imagejwatson_utah_edu ( 2016-07-30 18:03:32 -0600 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2016-07-31 18:46:16 -0600

That's just how spawn model works. There is nothing that should tie those two models together unless you write it. So I see two approaches:

1) Write a tiny plugin that looks at the position of the other model you're trying to follow and sets it's position relative to that. I believe a world plugin might be the best idea here, although model plugin is also probably possible. Check out both of them, I'm not sure which will be easier

2) Append to the existing model instead of spawning a new one. This time we definitely need a model plugin. Add a model plugin to your model that you can send a message to that will add/remove a static link to the model. Updating a model during runtime is definitely possible. If you need help with though search for other questions or make a new one.

edit flag offensive delete link more

Comments

@Peter_Mitrano, I will try these and let you know which one works.

jwatson_utah_edu gravatar imagejwatson_utah_edu ( 2016-08-02 16:36:21 -0600 )edit

@Peter_Mitrano, Option 1 mostly works although the results are kind of jittery. Dart does not seem to want to let me turn off gravity while the node does its position update work. ~ Now I have a new context that would be served by using Option 2, but I have not found a way to do this. See question below: http://answers.gazebosim.org/question/14072/how-to-programmatically-attach-link-to-a-model-during-simulation/

jwatson_utah_edu gravatar imagejwatson_utah_edu ( 2016-08-07 13:53:20 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2016-07-30 18:02:49 -0600

Seen: 2,474 times

Last updated: Jul 31 '16