Create joint at runtime via messages

asked 2016-03-26 10:13:58 -0600

gshopov gravatar image

I tried to create a joint that connects the following model

<?xml version='1.0'?>
<sdf version='1.4'>
    <model name="my_robot2">
        <static>false</static>
        <link name='chassis'>
            <pose>0 0 .1 0 0 0</pose>

            <collision name='collision'>
              <geometry>
                <box>
                  <size>.4 .2 .1</size>
                </box>
              </geometry>
            </collision>

            <visual name='visual'>
                <pose>0 0 0.05 0 0 0</pose>
                <geometry>
                    <mesh>
                        <uri>model://pioneer2dx/meshes/chassis.dae</uri>
                        <scale>0.9 0.5 0.5</scale>
                    </mesh>
                </geometry>
            </visual>

            <collision name='caster_collision'>
                <pose>-0.15 0 -0.05 0 0 0</pose>
                <geometry>
                    <sphere>
                        <radius>.05</radius>
                    </sphere>
                </geometry>

                <surface>
                    <friction>
                        <ode>
                            <mu>0</mu>
                            <mu2>0</mu2>
                            <slip1>1.0</slip1>
                            <slip2>1.0</slip2>
                        </ode>
                    </friction>
                </surface>
            </collision>

            <visual name='caster_visual'>
                <pose>-0.15 0 -0.05 0 0 0</pose>
                <geometry>
                    <sphere>
                        <radius>.05</radius>
                    </sphere>
                </geometry>
            </visual>
        </link>

        <link name="left_wheel">
            <pose>0.1 0.13 0.1 0 1.5707 1.5707</pose>
            <collision name="collision">
                <geometry>
                    <cylinder>
                        <radius>.1</radius>
                        <length>.05</length>
                    </cylinder>
                </geometry>
            </collision>

            <visual name="visual">
                <geometry>
                    <cylinder>
                        <radius>.1</radius>
                        <length>.05</length>
                    </cylinder>
                </geometry>
            </visual>
        </link>

        <link name="right_wheel">
            <pose>0.1 -0.13 0.1 0 1.5707 1.5707</pose>
            <collision name="collision">
                <geometry>
                    <cylinder>
                        <radius>.1</radius>
                        <length>.05</length>
                    </cylinder>
                </geometry>
            </collision>

            <visual name="visual">
                <geometry>
                    <cylinder>
                        <radius>.1</radius>
                        <length>.05</length>
                    </cylinder>
                </geometry>
            </visual>
        </link>

        <joint type="revolute" name="left_wheel_hinge">
            <pose>0 0 -0.03 0 0 0</pose>
            <child>left_wheel</child>
            <parent>chassis</parent>
            <axis>
                <xyz>0 1 0</xyz>
            </axis>
        </joint>

        <joint type="revolute" name="right_wheel_hinge">
            <pose>0 0 0.03 0 0 0</pose>
            <child>right_wheel</child>
            <parent>chassis</parent>
            <axis>
                <xyz>0 1 0</xyz>
            </axis>
        </joint>
    </model>
</sdf>

to a hokuyo (with pose (0.2, 0, 0.2, 0, 0, 0)) by sending a Joint message to /gazebo/default/joint. I set the following attributes of the message:

  • name: "hokuyo_joint"
  • child: "hokuyo::link"
  • parent: "my_robot2::chassis"
  • axis1: xyz set to (0, 0, 1); limit_lower, limit_upper, limit_effort, limit_velocity, damping, friction set to 0 and use_parent_mode_frame set to true

After sending the message I tried to move the robot but it moved separately from the hokuyo model. Am I using the correct topic and setting the correct attributes of the message or is it not yet possible to do that with messages?

edit retag flag offensive close merge delete